Rover: move try_send_message mission handling up

This commit is contained in:
Peter Barker 2017-07-18 21:03:26 +10:00 committed by Francisco Ferreira
parent de0c6d7ca5
commit 4da89a948a
2 changed files with 0 additions and 21 deletions

View File

@ -264,11 +264,6 @@ void Rover::send_pid_tuning(mavlink_channel_t chan)
}
}
void Rover::send_current_waypoint(mavlink_channel_t chan)
{
mavlink_msg_mission_current_send(chan, mission.get_current_nav_index());
}
void Rover::send_wheel_encoder(mavlink_channel_t chan)
{
// send wheel encoder data using rpm message
@ -387,21 +382,11 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id)
send_sensor_offsets(rover.ins, rover.compass, rover.barometer);
break;
case MSG_CURRENT_WAYPOINT:
CHECK_PAYLOAD_SIZE(MISSION_CURRENT);
rover.send_current_waypoint(chan);
break;
case MSG_NEXT_PARAM:
CHECK_PAYLOAD_SIZE(PARAM_VALUE);
queued_param_send();
break;
case MSG_NEXT_WAYPOINT:
CHECK_PAYLOAD_SIZE(MISSION_REQUEST);
queued_waypoint_send();
break;
case MSG_AHRS:
CHECK_PAYLOAD_SIZE(AHRS);
send_ahrs(rover.ahrs);
@ -464,11 +449,6 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id)
rover.send_pid_tuning(chan);
break;
case MSG_MISSION_ITEM_REACHED:
CHECK_PAYLOAD_SIZE(MISSION_ITEM_REACHED);
mavlink_msg_mission_item_reached_send(chan, mission_item_reached_index);
break;
case MSG_BATTERY_STATUS:
send_battery_status(rover.battery);
break;

View File

@ -461,7 +461,6 @@ private:
void send_hwstatus(mavlink_channel_t chan);
void send_pid_tuning(mavlink_channel_t chan);
void send_rangefinder(mavlink_channel_t chan);
void send_current_waypoint(mavlink_channel_t chan);
void send_wheel_encoder(mavlink_channel_t chan);
void gcs_data_stream_send(void);
void gcs_update(void);