Browse Source

Cut case MAVLINK_MSG_ID_RC_CHANNELS content and paste into handle_message_rc_channels() method.

sbg
mcsauder 6 years ago committed by Beat Küng
parent
commit
e43a0bbf1d
  1. 1
      src/modules/simulator/simulator.h
  2. 24
      src/modules/simulator/simulator_mavlink.cpp

1
src/modules/simulator/simulator.h

@ -337,6 +337,7 @@ private: @@ -337,6 +337,7 @@ private:
void handle_message_hil_state_quaternion(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 handle_message_rc_channels(const mavlink_message_t *msg);
void parameters_update(bool force);
void poll_topics();

24
src/modules/simulator/simulator_mavlink.cpp

@ -314,16 +314,7 @@ void Simulator::handle_message(mavlink_message_t *msg) @@ -314,16 +314,7 @@ void Simulator::handle_message(mavlink_message_t *msg)
break;
case MAVLINK_MSG_ID_RC_CHANNELS:
mavlink_rc_channels_t rc_channels;
mavlink_msg_rc_channels_decode(msg, &rc_channels);
fill_rc_input_msg(&_rc_input, &rc_channels);
// publish message
if (_publish) {
int rc_multi;
orb_publish_auto(ORB_ID(input_rc), &_rc_channels_pub, &_rc_input, &rc_multi, ORB_PRIO_HIGH);
}
handle_message_rc_channels(msg);
break;
case MAVLINK_MSG_ID_LANDING_TARGET: {
@ -539,6 +530,19 @@ void Simulator::handle_message_optical_flow(const mavlink_message_t *msg) @@ -539,6 +530,19 @@ void Simulator::handle_message_optical_flow(const mavlink_message_t *msg)
publish_flow_topic(&flow);
}
void Simulator::handle_message_rc_channels(const mavlink_message_t *msg)
{
mavlink_rc_channels_t rc_channels;
mavlink_msg_rc_channels_decode(msg, &rc_channels);
fill_rc_input_msg(&_rc_input, &rc_channels);
// publish message
if (_publish) {
int rc_multi;
orb_publish_auto(ORB_ID(input_rc), &_rc_channels_pub, &_rc_input, &rc_multi, ORB_PRIO_HIGH);
}
}
void Simulator::send_mavlink_message(const mavlink_message_t &aMsg)
{
uint8_t buf[MAVLINK_MAX_PACKET_LEN];

Loading…
Cancel
Save