Rover: move handling of incoming statutext messages up

This commit is contained in:
Peter Barker 2017-07-12 17:42:48 +10:00 committed by Francisco Ferreira
parent c9c4b31e99
commit 7aff4c6ab9
2 changed files with 7 additions and 14 deletions

View File

@ -279,6 +279,11 @@ void Rover::send_current_waypoint(mavlink_channel_t chan)
mavlink_msg_mission_current_send(chan, mission.get_current_nav_index());
}
uint8_t GCS_MAVLINK_Rover::sysid_my_gcs() const
{
return rover.g.sysid_my_gcs;
}
uint32_t GCS_MAVLINK_Rover::telem_delay() const
{
return static_cast<uint32_t>(rover.g.telem_delay);
@ -734,20 +739,6 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
break;
}
case MAVLINK_MSG_ID_STATUSTEXT:
{
// ignore any statustext messages not from our GCS:
if (msg->sysid != rover.g.sysid_my_gcs) {
break;
}
mavlink_statustext_t packet;
mavlink_msg_statustext_decode(msg, &packet);
char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1+4] = { 'G', 'C', 'S', ':'};
memcpy(&text[4], packet.text, MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
rover.DataFlash.Log_Write_Message(text);
break;
}
case MAVLINK_MSG_ID_COMMAND_INT: {
// decode packet
mavlink_command_int_t packet;

View File

@ -18,6 +18,8 @@ protected:
AP_Mission *get_mission() override;
uint8_t sysid_my_gcs() const override;
private:
void handleMessage(mavlink_message_t * msg) override;