Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Rover: Circle mode aux function support and SYSID_MYGCS param desc fix #25636

Merged
merged 9 commits into from
Nov 27, 2023
1 change: 1 addition & 0 deletions AntennaTracker/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@ const AP_Param::Info Tracker::var_info[] = {
// @DisplayName: Ground station MAVLink system ID
// @Description: The identifier of the ground station in the MAVLink protocol. Don't change this unless you also modify the ground station to match.
// @Range: 1 255
// @Increment: 1
// @User: Advanced
GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255),

Expand Down
1 change: 1 addition & 0 deletions ArduCopter/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@ const AP_Param::Info Copter::var_info[] = {
// @DisplayName: My ground station number
// @Description: Allows restricting radio overrides to only come from my ground station
// @Range: 1 255
// @Increment: 1
// @User: Advanced
GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255),

Expand Down
1 change: 1 addition & 0 deletions ArduPlane/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@ const AP_Param::Info Plane::var_info[] = {
// @DisplayName: Ground station MAVLink system ID
// @Description: The identifier of the ground station in the MAVLink protocol. Don't change this unless you also modify the ground station to match.
// @Range: 1 255
// @Increment: 1
// @User: Advanced
GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255),

Expand Down
2 changes: 2 additions & 0 deletions ArduSub/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,8 @@ const AP_Param::Info Sub::var_info[] = {
// @Param: SYSID_MYGCS
// @DisplayName: My ground station number
// @Description: Allows restricting radio overrides to only come from my ground station
// @Range: 1 255
// @Increment: 1
// @User: Advanced
GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255),

Expand Down
1 change: 1 addition & 0 deletions Blimp/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@ const AP_Param::Info Blimp::var_info[] = {
// @DisplayName: My ground station number
// @Description: Allows restricting radio overrides to only come from my ground station
// @Range: 1 255
// @Increment: 1
// @User: Advanced
GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255),

Expand Down
1 change: 1 addition & 0 deletions Rover/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@ const AP_Param::Info Rover::var_info[] = {
// @DisplayName: MAVLink ground station ID
// @Description: The identifier of the ground station in the MAVLink protocol. Don't change this unless you also modify the ground station to match.
// @Range: 1 255
// @Increment: 1
// @User: Advanced
GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255),

Expand Down
5 changes: 5 additions & 0 deletions Rover/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@ void RC_Channel_Rover::init_aux_function(const aux_func_t ch_option, const AuxSw
// the following functions do not need initialising:
case AUX_FUNC::ACRO:
case AUX_FUNC::AUTO:
case AUX_FUNC::CIRCLE:
case AUX_FUNC::FOLLOW:
case AUX_FUNC::GUIDED:
case AUX_FUNC::HOLD:
Expand Down Expand Up @@ -226,6 +227,10 @@ bool RC_Channel_Rover::do_aux_function(const aux_func_t ch_option, const AuxSwit
do_aux_function_change_mode(rover.mode_simple, ch_flag);
break;

case AUX_FUNC::CIRCLE:
do_aux_function_change_mode(rover.g2.mode_circle, ch_flag);
break;

// trigger sailboat tack
case AUX_FUNC::SAILBOAT_TACK:
// any switch movement interpreted as request to tack
Expand Down
2 changes: 1 addition & 1 deletion libraries/APM_Control/AR_PosControl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ const AP_Param::GroupInfo AR_PosControl::var_info[] = {
// @Param: _VEL_I
// @DisplayName: Velocity (horizontal) I gain
// @Description: Velocity (horizontal) I gain. Corrects long-term difference between desired and actual velocity to a target acceleration
// @Range: 0.02 1.00
// @Range: 0.00 1.00
// @Increment: 0.01
// @User: Advanced

Expand Down
2 changes: 1 addition & 1 deletion libraries/RC_Channel/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -171,7 +171,7 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = {
// @Values{Copter}: 69:POSHOLD Mode
// @Values{Copter}: 70:ALTHOLD Mode
// @Values{Copter}: 71:FLOWHOLD Mode
// @Values{Copter,Plane}: 72:CIRCLE Mode
// @Values{Copter,Rover,Plane}: 72:CIRCLE Mode
// @Values{Copter}: 73:DRIFT Mode
// @Values{Rover}: 74:Sailboat motoring 3pos
// @Values{Copter}: 75:SurfaceTrackingUpDown
Expand Down