|
|
|
@ -103,6 +103,7 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
@@ -103,6 +103,7 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
|
|
|
|
|
_flow_pub(-1), |
|
|
|
|
_offboard_control_sp_pub(-1), |
|
|
|
|
_local_pos_sp_pub(-1), |
|
|
|
|
_global_vel_sp_pub(-1), |
|
|
|
|
_att_sp_pub(-1), |
|
|
|
|
_rates_sp_pub(-1), |
|
|
|
|
_vicon_position_pub(-1), |
|
|
|
@ -365,30 +366,47 @@ MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message
@@ -365,30 +366,47 @@ MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message
|
|
|
|
|
case 1: |
|
|
|
|
ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_RATES; |
|
|
|
|
ml_armed = true; |
|
|
|
|
|
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case 2: |
|
|
|
|
ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE; |
|
|
|
|
ml_armed = true; |
|
|
|
|
|
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case 3: |
|
|
|
|
ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY; |
|
|
|
|
ml_armed = true; |
|
|
|
|
|
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case 4: |
|
|
|
|
ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_POSITION; |
|
|
|
|
ml_armed = true; |
|
|
|
|
|
|
|
|
|
break; |
|
|
|
|
default: |
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
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; |
|
|
|
|
if (m1_mode == OFFBOARD_CONTROL_MODE_DIRECT_RATES || m1_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) { |
|
|
|
|
|
|
|
|
|
/*Temporary hack to use set_quad_swarm_roll_pitch_yaw_thrust msg for position or velocity */
|
|
|
|
|
/* Converts INT16 centimeters to float meters */ |
|
|
|
|
offboard_control_sp.p1 = (float)quad_motors_setpoint.roll[mavlink_system.sysid - 1] / 100.0f; |
|
|
|
|
offboard_control_sp.p2 = (float)quad_motors_setpoint.pitch[mavlink_system.sysid - 1] / 100.0f; |
|
|
|
|
offboard_control_sp.p3 = (float)quad_motors_setpoint.yaw[mavlink_system.sysid - 1] / 100.0f; |
|
|
|
|
offboard_control_sp.p4 = (float)quad_motors_setpoint.thrust[mavlink_system.sysid - 1] / 100.0f; |
|
|
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (quad_motors_setpoint.thrust[mavlink_system.sysid - 1] == 0) { |
|
|
|
|
ml_armed = false; |
|
|
|
@ -420,7 +438,7 @@ MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message
@@ -420,7 +438,7 @@ MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message
|
|
|
|
|
loc_pos_sp.x = offboard_control_sp.p1; |
|
|
|
|
loc_pos_sp.y = offboard_control_sp.p2; |
|
|
|
|
loc_pos_sp.yaw = offboard_control_sp.p3; |
|
|
|
|
loc_pos_sp.z = offboard_control_sp.p4; |
|
|
|
|
loc_pos_sp.z = -offboard_control_sp.p4; |
|
|
|
|
|
|
|
|
|
/* Close fds to allow position controller to use attitude controller */ |
|
|
|
|
if (_att_sp_pub > 0) { |
|
|
|
@ -433,6 +451,11 @@ MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message
@@ -433,6 +451,11 @@ MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message
|
|
|
|
|
_rates_sp_pub = -1; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (_global_vel_sp_pub > 0) { |
|
|
|
|
close(_global_vel_sp_pub); |
|
|
|
|
_global_vel_sp_pub = -1; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (_local_pos_sp_pub < 0) { |
|
|
|
|
_local_pos_sp_pub = orb_advertise(ORB_ID(vehicle_local_position_setpoint), &_local_pos_sp_pub); |
|
|
|
|
|
|
|
|
@ -441,7 +464,30 @@ MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message
@@ -441,7 +464,30 @@ MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
} else if (_control_mode.flag_control_velocity_enabled) { |
|
|
|
|
// TODO
|
|
|
|
|
/* velocity control */ |
|
|
|
|
struct vehicle_global_velocity_setpoint_s global_vel_sp; |
|
|
|
|
memset(&global_vel_sp, 0, sizeof(&global_vel_sp)); |
|
|
|
|
|
|
|
|
|
global_vel_sp.vx = offboard_control_sp.p1; |
|
|
|
|
global_vel_sp.vy = offboard_control_sp.p2; |
|
|
|
|
global_vel_sp.vz = offboard_control_sp.p3; |
|
|
|
|
|
|
|
|
|
if (_att_sp_pub > 0) { |
|
|
|
|
close(_att_sp_pub); |
|
|
|
|
_att_sp_pub = -1; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (_rates_sp_pub > 0) { |
|
|
|
|
close(_rates_sp_pub); |
|
|
|
|
_rates_sp_pub = -1; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (_global_vel_sp_pub < 0) { |
|
|
|
|
_global_vel_sp_pub = orb_advertise(ORB_ID(vehicle_global_velocity_setpoint_s), &_global_vel_sp_pub); |
|
|
|
|
|
|
|
|
|
} else { |
|
|
|
|
orb_publish(ORB_ID(vehicle_global_velocity_setpoint_s), _global_vel_sp_pub, &global_vel_sp); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
} else if (_control_mode.flag_control_attitude_enabled) { |
|
|
|
|
/* attitude control */ |
|
|
|
@ -1021,6 +1067,11 @@ MavlinkReceiver::receive_thread(void *arg)
@@ -1021,6 +1067,11 @@ MavlinkReceiver::receive_thread(void *arg)
|
|
|
|
|
_local_pos_sp_pub = -1; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (_global_vel_sp_pub > 0) { |
|
|
|
|
close(_global_vel_sp_pub); |
|
|
|
|
_global_vel_sp_pub = -1; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (_att_sp_pub > 0) { |
|
|
|
|
close(_att_sp_pub); |
|
|
|
|
_att_sp_pub = -1; |
|
|
|
|