aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp8
-rw-r--r--src/modules/mc_pos_control/mc_pos_control_main.cpp9
2 files changed, 9 insertions, 8 deletions
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index 8a00509a4..c95ee880c 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -390,14 +390,14 @@ MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message
break;
}
- if (m1_mode == OFFBOARD_CONTROL_MODE_DIRECT_RATES || m1_mode == OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE) {
+ if (ml_mode == OFFBOARD_CONTROL_MODE_DIRECT_RATES || ml_mode == OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE) {
offboard_control_sp.p1 = (float)quad_motors_setpoint.roll[mavlink_system.sysid - 1] / (float)INT16_MAX;
offboard_control_sp.p2 = (float)quad_motors_setpoint.pitch[mavlink_system.sysid - 1] / (float)INT16_MAX;
offboard_control_sp.p3 = (float)quad_motors_setpoint.yaw[mavlink_system.sysid - 1] / (float)INT16_MAX;
offboard_control_sp.p4 = (float)quad_motors_setpoint.thrust[mavlink_system.sysid - 1] / (float)UINT16_MAX;
- } else if (m1_mode == OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY || m1_mode == OFFBOARD_CONTROL_MODE_DIRECT_POSITION) {
+ } else if (ml_mode == OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY || ml_mode == OFFBOARD_CONTROL_MODE_DIRECT_POSITION) {
/*Temporary hack to use set_quad_swarm_roll_pitch_yaw_thrust msg for position or velocity */
/* Converts INT16 centimeters to float meters */
@@ -483,10 +483,10 @@ MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message
}
if (_global_vel_sp_pub < 0) {
- _global_vel_sp_pub = orb_advertise(ORB_ID(vehicle_global_velocity_setpoint_s), &_global_vel_sp_pub);
+ _global_vel_sp_pub = orb_advertise(ORB_ID(vehicle_global_velocity_setpoint), &_global_vel_sp_pub);
} else {
- orb_publish(ORB_ID(vehicle_global_velocity_setpoint_s), _global_vel_sp_pub, &global_vel_sp);
+ orb_publish(ORB_ID(vehicle_global_velocity_setpoint), _global_vel_sp_pub, &global_vel_sp);
}
} else if (_control_mode.flag_control_attitude_enabled) {
diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp
index 53394b41c..86112fa21 100644
--- a/src/modules/mc_pos_control/mc_pos_control_main.cpp
+++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp
@@ -117,9 +117,9 @@ private:
int _manual_sub; /**< notification of manual control updates */
int _arming_sub; /**< arming status of outputs */
int _local_pos_sub; /**< vehicle local position */
- int _pos_sp_triplet_sub; /**< position setpoint triplet */
- int _local_pos_sp_sub; /**< offboard local position setpoint */
- int _global_vel_sp_sub; /**< offboard global velocity setpoint */
+ int _pos_sp_triplet_sub; /**< position setpoint triplet */
+ int _local_pos_sp_sub; /**< offboard local position setpoint */
+ int _global_vel_sp_sub; /**< offboard global velocity setpoint */
orb_advert_t _att_sp_pub; /**< attitude setpoint publication */
orb_advert_t _local_pos_sp_pub; /**< vehicle local position setpoint publication */
@@ -802,6 +802,7 @@ MulticopterPositionControl::task_main()
if (!_control_mode.flag_control_position_enabled && _control_mode.flag_control_velocity_enabled) {
_vel_sp(0) = _global_vel_sp.vx;
_vel_sp(1) = _global_vel_sp.vy;
+ }
}
if (!_control_mode.flag_control_manual_enabled) {
@@ -827,7 +828,7 @@ MulticopterPositionControl::task_main()
/* Close fd to let offboard vel sp be advertised in mavlink receiver */
if (_control_mode.flag_control_offboard_enabled && _global_vel_sp_pub > 0) {
- close (_global_vel_sp);
+ close(_global_vel_sp_pub);
_global_vel_sp_pub = -1;
}