File tree Expand file tree Collapse file tree 2 files changed +14
-0
lines changed Expand file tree Collapse file tree 2 files changed +14
-0
lines changed Original file line number Diff line number Diff line change @@ -675,6 +675,14 @@ void GCS_MAVLINK_Rover::handle_set_attitude_target(const mavlink_message_t &msg)
675
675
}
676
676
}
677
677
678
+ // if we receive a message where the user has not masked out
679
+ // acceleration from the input packet we send a curt message
680
+ // informing them:
681
+ void GCS_MAVLINK_Rover::send_acc_ignore_must_be_set_message (const char *msgname)
682
+ {
683
+ GCS_SEND_TEXT (MAV_SEVERITY_INFO, " Ignoring %s; set ACC_IGNORE in mask" , msgname);
684
+ }
685
+
678
686
void GCS_MAVLINK_Rover::handle_set_position_target_local_ned (const mavlink_message_t &msg)
679
687
{
680
688
// decode packet
@@ -782,6 +790,7 @@ void GCS_MAVLINK_Rover::handle_set_position_target_local_ned(const mavlink_messa
782
790
783
791
if (!acc_ignore) {
784
792
// ignore any command where acceleration is not ignored
793
+ send_acc_ignore_must_be_set_message (" SET_POSITION_TARGET_LOCAL_NED" );
785
794
return ;
786
795
}
787
796
@@ -891,6 +900,7 @@ void GCS_MAVLINK_Rover::handle_set_position_target_global_int(const mavlink_mess
891
900
892
901
if (!acc_ignore) {
893
902
// ignore any command where acceleration is not ignored
903
+ send_acc_ignore_must_be_set_message (" SET_POSITION_TARGET_GLOBAL_INT" );
894
904
return ;
895
905
}
896
906
Original file line number Diff line number Diff line change @@ -52,6 +52,10 @@ class GCS_MAVLINK_Rover : public GCS_MAVLINK
52
52
53
53
void send_servo_out ();
54
54
55
+ // if we receive a message where the user has not masked out
56
+ // acceleration from the input packet we send a curt message
57
+ // informing them:
58
+ void send_acc_ignore_must_be_set_message (const char *msgname);
55
59
uint8_t base_mode () const override ;
56
60
MAV_STATE vehicle_system_status () const override ;
57
61
You can’t perform that action at this time.
0 commit comments