Skip to content

Commit

Permalink
Cut case MAVLINK_MSG_ID_LANDING_TARGET content and paste into handle_…
Browse files Browse the repository at this point in the history
…message_landing_target() method.
  • Loading branch information
mcsauder authored and bkueng committed Feb 28, 2019
1 parent 0df34af commit 411db78
Show file tree
Hide file tree
Showing 2 changed files with 21 additions and 15 deletions.
2 changes: 2 additions & 0 deletions src/modules/simulator/simulator.h
Original file line number Diff line number Diff line change
Expand Up @@ -331,6 +331,8 @@ class Simulator : public ModuleParams
mavlink_hil_actuator_controls_t actuator_controls_from_outputs(const actuator_outputs_s &actuators);

void handle_message(mavlink_message_t *msg, bool publish);
void handle_message_landing_target(const mavlink_message_t *msg);

void parameters_update(bool force);
void poll_topics();
void pollForMAVLinkMessages(bool publish);
Expand Down
34 changes: 19 additions & 15 deletions src/modules/simulator/simulator_mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -398,21 +398,7 @@ void Simulator::handle_message(mavlink_message_t *msg, bool publish)
break;

case MAVLINK_MSG_ID_LANDING_TARGET: {
mavlink_landing_target_t landing_target_mavlink;
mavlink_msg_landing_target_decode(msg, &landing_target_mavlink);

struct irlock_report_s report = {};

report.timestamp = hrt_absolute_time();
report.signature = landing_target_mavlink.target_num;
report.pos_x = landing_target_mavlink.angle_x;
report.pos_y = landing_target_mavlink.angle_y;
report.size_x = landing_target_mavlink.size_x;
report.size_y = landing_target_mavlink.size_y;

int irlock_multi;
orb_publish_auto(ORB_ID(irlock_report), &_irlock_report_pub, &report, &irlock_multi, ORB_PRIO_HIGH);

handle_message_landing_target(msg);
break;
}

Expand Down Expand Up @@ -513,6 +499,24 @@ void Simulator::handle_message(mavlink_message_t *msg, bool publish)

}

void Simulator::handle_message_landing_target(const mavlink_message_t *msg)
{
mavlink_landing_target_t landing_target_mavlink;
mavlink_msg_landing_target_decode(msg, &landing_target_mavlink);

struct irlock_report_s report = {};

report.timestamp = hrt_absolute_time();
report.signature = landing_target_mavlink.target_num;
report.pos_x = landing_target_mavlink.angle_x;
report.pos_y = landing_target_mavlink.angle_y;
report.size_x = landing_target_mavlink.size_x;
report.size_y = landing_target_mavlink.size_y;

int irlock_multi;
orb_publish_auto(ORB_ID(irlock_report), &_irlock_report_pub, &report, &irlock_multi, ORB_PRIO_HIGH);
}

void Simulator::send_mavlink_message(const mavlink_message_t &aMsg)
{
uint8_t buf[MAVLINK_MAX_PACKET_LEN];
Expand Down

0 comments on commit 411db78

Please sign in to comment.