diff --git a/src/modules/simulator/simulator.h b/src/modules/simulator/simulator.h index dbbceae4d5..53f500910a 100644 --- a/src/modules/simulator/simulator.h +++ b/src/modules/simulator/simulator.h @@ -333,6 +333,7 @@ private: void handle_message(mavlink_message_t *msg, bool publish); void handle_message_distance_sensor(const mavlink_message_t *msg); void handle_message_landing_target(const mavlink_message_t *msg); + void handle_message_optical_flow(const mavlink_message_t *msg); void parameters_update(bool force); void poll_topics(); diff --git a/src/modules/simulator/simulator_mavlink.cpp b/src/modules/simulator/simulator_mavlink.cpp index 2452cd54b8..6801da32f7 100644 --- a/src/modules/simulator/simulator_mavlink.cpp +++ b/src/modules/simulator/simulator_mavlink.cpp @@ -357,9 +357,7 @@ void Simulator::handle_message(mavlink_message_t *msg, bool publish) break; case MAVLINK_MSG_ID_HIL_OPTICAL_FLOW: - mavlink_hil_optical_flow_t flow; - mavlink_msg_hil_optical_flow_decode(msg, &flow); - publish_flow_topic(&flow); + handle_message_optical_flow(msg); break; case MAVLINK_MSG_ID_ODOMETRY: @@ -522,6 +520,13 @@ void Simulator::handle_message_landing_target(const mavlink_message_t *msg) orb_publish_auto(ORB_ID(irlock_report), &_irlock_report_pub, &report, &irlock_multi, ORB_PRIO_HIGH); } +void Simulator::handle_message_optical_flow(const mavlink_message_t *msg) +{ + mavlink_hil_optical_flow_t flow; + mavlink_msg_hil_optical_flow_decode(msg, &flow); + publish_flow_topic(&flow); +} + void Simulator::send_mavlink_message(const mavlink_message_t &aMsg) { uint8_t buf[MAVLINK_MAX_PACKET_LEN];