mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Rover: reindent all of the new GCS_MAVLink handling methods (NFC)
This commit is contained in:
parent
2240a60e20
commit
0273d92887
@ -779,7 +779,7 @@ void GCS_MAVLINK_Rover::handleMessage(const mavlink_message_t &msg)
|
||||
}
|
||||
|
||||
void GCS_MAVLINK_Rover::handle_manual_control(const mavlink_message_t &msg)
|
||||
{
|
||||
{
|
||||
if (msg.sysid != rover.g.sysid_my_gcs) { // Only accept control from our gcs
|
||||
return;
|
||||
}
|
||||
@ -798,19 +798,19 @@ void GCS_MAVLINK_Rover::handle_manual_control(const mavlink_message_t &msg)
|
||||
|
||||
// a manual control message is considered to be a 'heartbeat' from the ground station for failsafe purposes
|
||||
rover.failsafe.last_heartbeat_ms = tnow;
|
||||
}
|
||||
}
|
||||
|
||||
void GCS_MAVLINK_Rover::handle_heartbeat(const mavlink_message_t &msg)
|
||||
{
|
||||
{
|
||||
// we keep track of the last time we received a heartbeat from our GCS for failsafe purposes
|
||||
if (msg.sysid != rover.g.sysid_my_gcs) {
|
||||
return;
|
||||
}
|
||||
rover.failsafe.last_heartbeat_ms = AP_HAL::millis();
|
||||
}
|
||||
}
|
||||
|
||||
void GCS_MAVLINK_Rover::handle_set_attitude_target(const mavlink_message_t &msg)
|
||||
{
|
||||
{
|
||||
// decode packet
|
||||
mavlink_set_attitude_target_t packet;
|
||||
mavlink_msg_set_attitude_target_decode(&msg, &packet);
|
||||
@ -838,10 +838,10 @@ void GCS_MAVLINK_Rover::handle_set_attitude_target(const mavlink_message_t &msg)
|
||||
// use body_yaw_rate field
|
||||
rover.mode_guided.set_desired_turn_rate_and_speed((RAD_TO_DEG * packet.body_yaw_rate) * 100.0f, target_speed);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void GCS_MAVLINK_Rover::handle_set_position_target_local_ned(const mavlink_message_t &msg)
|
||||
{
|
||||
{
|
||||
// decode packet
|
||||
mavlink_set_position_target_local_ned_t packet;
|
||||
mavlink_msg_set_position_target_local_ned_decode(&msg, &packet);
|
||||
@ -964,10 +964,10 @@ void GCS_MAVLINK_Rover::handle_set_position_target_local_ned(const mavlink_messa
|
||||
// consume just turn rate (probably only skid steering vehicles can do this)
|
||||
rover.mode_guided.set_desired_turn_rate_and_speed(target_turn_rate_cds, 0.0f);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void GCS_MAVLINK_Rover::handle_set_position_target_global_int(const mavlink_message_t &msg)
|
||||
{
|
||||
{
|
||||
// decode packet
|
||||
mavlink_set_position_target_global_int_t packet;
|
||||
mavlink_msg_set_position_target_global_int_decode(&msg, &packet);
|
||||
@ -1068,11 +1068,11 @@ void GCS_MAVLINK_Rover::handle_set_position_target_global_int(const mavlink_mess
|
||||
// consume just turn rate(probably only skid steering vehicles can do this)
|
||||
rover.mode_guided.set_desired_turn_rate_and_speed(target_turn_rate_cds, 0.0f);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#if HIL_MODE != HIL_MODE_DISABLED
|
||||
void GCS_MAVLINK_Rover::handle_hil_state(const mavlink_message_t &msg)
|
||||
{
|
||||
{
|
||||
mavlink_hil_state_t packet;
|
||||
mavlink_msg_hil_state_decode(&msg, &packet);
|
||||
|
||||
@ -1110,13 +1110,13 @@ void GCS_MAVLINK_Rover::handle_hil_state(const mavlink_message_t &msg)
|
||||
ins.set_accel(0, accels);
|
||||
compass.setHIL(0, packet.roll, packet.pitch, packet.yaw);
|
||||
compass.setHIL(1, packet.roll, packet.pitch, packet.yaw);
|
||||
}
|
||||
}
|
||||
#endif // HIL_MODE
|
||||
|
||||
void GCS_MAVLINK_Rover::handle_radio(const mavlink_message_t &msg)
|
||||
{
|
||||
{
|
||||
handle_radio_status(msg, rover.should_log(MASK_LOG_PM));
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
uint64_t GCS_MAVLINK_Rover::capabilities() const
|
||||
|
Loading…
Reference in New Issue
Block a user