Skip to content

Commit

Permalink
simulator: fix to set system and component IDs as defined in params
Browse files Browse the repository at this point in the history
The simulator had hardcoded component ID and system ID (sysID was 0), ignoring what was set up in the params MAV_SYS_ID and MAV_COMP_ID. This caused an issue with multi-vehicle simulations that that rely on sysID to identify the vehicles.

Signed-off-by: Gabriel Moreno <gabrielm@cs.cmu.edu>
  • Loading branch information
gamoreno authored and LorenzMeier committed Mar 3, 2019
1 parent 951f331 commit fc7c7ac
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 4 deletions.
4 changes: 3 additions & 1 deletion src/modules/simulator/simulator.h
Original file line number Diff line number Diff line change
Expand Up @@ -378,7 +378,9 @@ class Simulator : public ModuleParams

DEFINE_PARAMETERS(
(ParamFloat<px4::params::SIM_BAT_DRAIN>) _battery_drain_interval_s, ///< battery drain interval
(ParamInt<px4::params::MAV_TYPE>) _param_system_type
(ParamInt<px4::params::MAV_TYPE>) _param_system_type,
(ParamInt<px4::params::MAV_SYS_ID>) _param_system_id,
(ParamInt<px4::params::MAV_COMP_ID>) _param_component_id
)

#endif
Expand Down
6 changes: 3 additions & 3 deletions src/modules/simulator/simulator_mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -184,7 +184,7 @@ void Simulator::send_controls()
const mavlink_hil_actuator_controls_t hil_act_control = actuator_controls_from_outputs(actuators);

mavlink_message_t message{};
mavlink_msg_hil_actuator_controls_encode(0, 200, &message, &hil_act_control);
mavlink_msg_hil_actuator_controls_encode(_param_system_id.get(), _param_component_id.get(), &message, &hil_act_control);

PX4_DEBUG("sending controls t=%ld (%ld)", actuators.timestamp, hil_act_control.time_usec);

Expand Down Expand Up @@ -618,7 +618,7 @@ void Simulator::request_hil_state_quaternion()
cmd_long.command = MAV_CMD_SET_MESSAGE_INTERVAL;
cmd_long.param1 = MAVLINK_MSG_ID_HIL_STATE_QUATERNION;
cmd_long.param2 = 5e3;
mavlink_msg_command_long_encode(0, 50, &message, &cmd_long);
mavlink_msg_command_long_encode(_param_system_id.get(), _param_component_id.get(), &message, &cmd_long);
send_mavlink_message(message);
}

Expand All @@ -628,7 +628,7 @@ void Simulator::send_heartbeat()
mavlink_message_t message = {};
hb.autopilot = 12;
hb.base_mode |= (_vehicle_status.arming_state == vehicle_status_s::ARMING_STATE_ARMED) ? 128 : 0;
mavlink_msg_heartbeat_encode(0, 50, &message, &hb);
mavlink_msg_heartbeat_encode(_param_system_id.get(), _param_component_id.get(), &message, &hb);
send_mavlink_message(message);
}

Expand Down

0 comments on commit fc7c7ac

Please sign in to comment.