diff --git a/src/modules/simulator/simulator.h b/src/modules/simulator/simulator.h index 6099339c44bd13ab966d9701fb44107aba0d8207..5aa663542c8d54be7529d99c40273338a8bdfec9 100644 --- a/src/modules/simulator/simulator.h +++ b/src/modules/simulator/simulator.h @@ -332,6 +332,7 @@ private: void handle_message(mavlink_message_t *msg); void handle_message_distance_sensor(const mavlink_message_t *msg); + void handle_message_hil_gps(const mavlink_message_t *msg); void handle_message_hil_sensor(const mavlink_message_t *msg); void handle_message_hil_state_quaternion(const mavlink_message_t *msg); void handle_message_landing_target(const mavlink_message_t *msg); diff --git a/src/modules/simulator/simulator_mavlink.cpp b/src/modules/simulator/simulator_mavlink.cpp index aa3f3a853d6807a18757904969068c01dbdf9c61..f13661f48e57a86994ccad066b24533f434e1bd2 100644 --- a/src/modules/simulator/simulator_mavlink.cpp +++ b/src/modules/simulator/simulator_mavlink.cpp @@ -310,14 +310,7 @@ void Simulator::handle_message(mavlink_message_t *msg) break; case MAVLINK_MSG_ID_HIL_GPS: - mavlink_hil_gps_t gps_sim; - mavlink_msg_hil_gps_decode(msg, &gps_sim); - - if (_publish) { - //PX4_WARN("FIXME: Need to publish GPS topic. Not done yet."); - } - - update_gps(&gps_sim); + handle_message_hil_gps(msg); break; case MAVLINK_MSG_ID_RC_CHANNELS: @@ -351,6 +344,18 @@ void Simulator::handle_message_distance_sensor(const mavlink_message_t *msg) publish_distance_topic(&dist); } +void Simulator::handle_message_hil_gps(const mavlink_message_t *msg) +{ + mavlink_hil_gps_t gps_sim; + mavlink_msg_hil_gps_decode(msg, &gps_sim); + + if (_publish) { + //PX4_WARN("FIXME: Need to publish GPS topic. Not done yet."); + } + + update_gps(&gps_sim); +} + void Simulator::handle_message_hil_sensor(const mavlink_message_t *msg) { mavlink_hil_sensor_t imu;