aboutsummaryrefslogtreecommitdiff
path: root/src
diff options
context:
space:
mode:
Diffstat (limited to 'src')
-rw-r--r--src/modules/commander/commander.cpp33
-rw-r--r--src/modules/mavlink/mavlink.c7
-rw-r--r--src/modules/mavlink/mavlink_main.cpp16
-rw-r--r--src/modules/mavlink/mavlink_main.h8
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp169
-rw-r--r--src/modules/mavlink/mavlink_receiver.h2
-rw-r--r--src/modules/navigator/offboard.cpp77
-rw-r--r--src/modules/uORB/topics/offboard_control_setpoint.h55
-rw-r--r--src/modules/uORB/topics/vehicle_command.h3
9 files changed, 309 insertions, 61 deletions
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index 0c4d48dea..e9db923e6 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -611,7 +611,24 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s
}
}
break;
-
+ case VEHICLE_CMD_NAV_GUIDED_ENABLE: {
+ transition_result_t res = TRANSITION_DENIED;
+ static main_state_t main_state_pre_offboard = MAIN_STATE_MANUAL;
+ if (status_local->main_state != MAIN_STATE_OFFBOARD) {
+ main_state_pre_offboard = status_local->main_state;
+ }
+ if (cmd->param1 > 0.5f) {
+ res = main_state_transition(status_local, MAIN_STATE_OFFBOARD);
+ if (res == TRANSITION_DENIED) {
+ print_reject_mode(status_local, "OFFBOARD");
+ }
+ } else {
+ /* If the mavlink command is used to enable or disable offboard control:
+ * switch back to previous mode when disabling */
+ res = main_state_transition(status_local, main_state_pre_offboard);
+ }
+ }
+ break;
case VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
case VEHICLE_CMD_PREFLIGHT_CALIBRATION:
case VEHICLE_CMD_PREFLIGHT_SET_SENSOR_OFFSETS:
@@ -1924,21 +1941,17 @@ set_control_mode()
control_mode.flag_control_position_enabled = false;
control_mode.flag_control_velocity_enabled = false;
break;
- case OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY:
- control_mode.flag_control_rates_enabled = true;
- control_mode.flag_control_attitude_enabled = true;
- control_mode.flag_control_altitude_enabled = true; /* XXX: hack for now */
- control_mode.flag_control_climb_rate_enabled = true;
- control_mode.flag_control_position_enabled = true; /* XXX: hack for now */
- control_mode.flag_control_velocity_enabled = true;
- break;
- case OFFBOARD_CONTROL_MODE_DIRECT_POSITION:
+ case OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_NED:
+ case OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_OFFSET_NED:
+ case OFFBOARD_CONTROL_MODE_DIRECT_BODY_NED:
+ case OFFBOARD_CONTROL_MODE_DIRECT_BODY_OFFSET_NED:
control_mode.flag_control_rates_enabled = true;
control_mode.flag_control_attitude_enabled = true;
control_mode.flag_control_altitude_enabled = true;
control_mode.flag_control_climb_rate_enabled = true;
control_mode.flag_control_position_enabled = true;
control_mode.flag_control_velocity_enabled = true;
+ //XXX: the flags could depend on sp_offboard.ignore
break;
default:
control_mode.flag_control_rates_enabled = false;
diff --git a/src/modules/mavlink/mavlink.c b/src/modules/mavlink/mavlink.c
index e49288a74..bec706bad 100644
--- a/src/modules/mavlink/mavlink.c
+++ b/src/modules/mavlink/mavlink.c
@@ -68,6 +68,13 @@ PARAM_DEFINE_INT32(MAV_TYPE, MAV_TYPE_FIXED_WING);
* @group MAVLink
*/
PARAM_DEFINE_INT32(MAV_USEHILGPS, 0);
+/**
+ * Forward external setpoint messages
+ * If set to 1 incomming external setpoint messages will be directly forwarded to the controllers if in offboard
+ * control mode
+ * @group MAVLink
+ */
+PARAM_DEFINE_INT32(MAV_FWDEXTSP, 1);
mavlink_system_t mavlink_system = {
100,
diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp
index cd0581af4..7707c0bc8 100644
--- a/src/modules/mavlink/mavlink_main.cpp
+++ b/src/modules/mavlink/mavlink_main.cpp
@@ -220,6 +220,7 @@ Mavlink::Mavlink() :
_task_running(false),
_hil_enabled(false),
_use_hil_gps(false),
+ _forward_externalsp(false),
_is_usb_uart(false),
_wait_to_transmit(false),
_received_messages(false),
@@ -246,6 +247,7 @@ Mavlink::Mavlink() :
_param_component_id(0),
_param_system_type(0),
_param_use_hil_gps(0),
+ _param_forward_externalsp(0),
/* performance counters */
_loop_perf(perf_alloc(PC_ELAPSED, "mavlink_el")),
@@ -517,6 +519,7 @@ void Mavlink::mavlink_update_system(void)
_param_component_id = param_find("MAV_COMP_ID");
_param_system_type = param_find("MAV_TYPE");
_param_use_hil_gps = param_find("MAV_USEHILGPS");
+ _param_forward_externalsp = param_find("MAV_FWDEXTSP");
_param_initialized = true;
}
@@ -546,6 +549,11 @@ void Mavlink::mavlink_update_system(void)
param_get(_param_use_hil_gps, &use_hil_gps);
_use_hil_gps = (bool)use_hil_gps;
+
+ int32_t forward_externalsp;
+ param_get(_param_forward_externalsp, &forward_externalsp);
+
+ _forward_externalsp = (bool)forward_externalsp;
}
int Mavlink::get_system_id()
@@ -1501,14 +1509,14 @@ Mavlink::task_main(int argc, char *argv[])
if (read_count > sizeof(mavlink_message_t)) {
read_count = sizeof(mavlink_message_t);
}
-
+
memcpy(write_ptr, read_ptr, read_count);
-
+
// We hold the mutex until after we complete the second part of the buffer. If we don't
// we may end up breaking the empty slot overflow detection semantics when we mark the
// possibly partial read below.
pthread_mutex_lock(&_message_buffer_mutex);
-
+
message_buffer_mark_read(read_count);
/* write second part of buffer if there is some */
@@ -1519,7 +1527,7 @@ Mavlink::task_main(int argc, char *argv[])
memcpy(write_ptr, read_ptr, read_count);
message_buffer_mark_read(available);
}
-
+
pthread_mutex_unlock(&_message_buffer_mutex);
_mavlink_resend_uart(_channel, &msg);
diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h
index acfc8b90e..8738a6f18 100644
--- a/src/modules/mavlink/mavlink_main.h
+++ b/src/modules/mavlink/mavlink_main.h
@@ -134,6 +134,8 @@ public:
bool get_use_hil_gps() { return _use_hil_gps; }
+ bool get_forward_externalsp() { return _forward_externalsp; }
+
bool get_flow_control_enabled() { return _flow_control_enabled; }
bool get_forwarding_on() { return _forwarding_on; }
@@ -205,7 +207,7 @@ public:
* Send a status text with loglevel
*
* @param string the message to send (will be capped by mavlink max string length)
- * @param severity the log level, one of
+ * @param severity the log level, one of
*/
int send_statustext(unsigned severity, const char *string);
MavlinkStream * get_streams() const { return _streams; }
@@ -220,7 +222,7 @@ public:
bool should_transmit() { return (!_wait_to_transmit || (_wait_to_transmit && _received_messages)); }
bool message_buffer_write(const void *ptr, int size);
-
+
void lockMessageBufferMutex(void) { pthread_mutex_lock(&_message_buffer_mutex); }
void unlockMessageBufferMutex(void) { pthread_mutex_unlock(&_message_buffer_mutex); }
@@ -241,6 +243,7 @@ private:
/* states */
bool _hil_enabled; /**< Hardware In the Loop mode */
bool _use_hil_gps; /**< Accept GPS HIL messages (for example from an external motion capturing system to fake indoor gps) */
+ bool _forward_externalsp; /**< Forward external setpoint messages to controllers directly if in offboard mode */
bool _is_usb_uart; /**< Port is USB */
bool _wait_to_transmit; /**< Wait to transmit until received messages. */
bool _received_messages; /**< Whether we've received valid mavlink messages. */
@@ -301,6 +304,7 @@ private:
param_t _param_component_id;
param_t _param_system_type;
param_t _param_use_hil_gps;
+ param_t _param_forward_externalsp;
perf_counter_t _loop_perf; /**< loop performance counter */
perf_counter_t _txerr_perf; /**< TX error counter */
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index 99ec98ee9..9e3842614 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -153,6 +153,14 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
handle_message_quad_swarm_roll_pitch_yaw_thrust(msg);
break;
+ case MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL:
+ handle_message_local_ned_position_setpoint_external(msg);
+ break;
+
+ case MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL:
+ handle_message_attitude_setpoint_external(msg);
+ break;
+
case MAVLINK_MSG_ID_RADIO_STATUS:
handle_message_radio_status(msg);
break;
@@ -374,10 +382,11 @@ MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message
memset(&offboard_control_sp, 0, sizeof(offboard_control_sp));
/* Convert values * 1000 back */
- offboard_control_sp.p1 = (float)swarm_offboard_control.roll[mavlink_system.sysid - 1] / 1000.0f;
- offboard_control_sp.p2 = (float)swarm_offboard_control.pitch[mavlink_system.sysid - 1] / 1000.0f;
- offboard_control_sp.p3 = (float)swarm_offboard_control.yaw[mavlink_system.sysid - 1] / 1000.0f;
- offboard_control_sp.p4 = (float)swarm_offboard_control.thrust[mavlink_system.sysid - 1] / 1000.0f;
+ //XXX: convert to quaternion
+ //offboard_control_sp.p1 = (float)swarm_offboard_control.roll[mavlink_system.sysid - 1] / 1000.0f;
+ //offboard_control_sp.p2 = (float)swarm_offboard_control.pitch[mavlink_system.sysid - 1] / 1000.0f;
+ //offboard_control_sp.p3 = (float)swarm_offboard_control.yaw[mavlink_system.sysid - 1] / 1000.0f;
+ //offboard_control_sp.p4 = (float)swarm_offboard_control.thrust[mavlink_system.sysid - 1] / 1000.0f;
offboard_control_sp.mode = (enum OFFBOARD_CONTROL_MODE)swarm_offboard_control.mode;
@@ -393,6 +402,158 @@ MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message
}
void
+MavlinkReceiver::handle_message_local_ned_position_setpoint_external(mavlink_message_t *msg)
+{
+ mavlink_local_ned_position_setpoint_external_t local_ned_position_setpoint_external;
+ mavlink_msg_local_ned_position_setpoint_external_decode(msg, &local_ned_position_setpoint_external);
+
+ struct offboard_control_setpoint_s offboard_control_sp;
+ memset(&offboard_control_sp, 0, sizeof(offboard_control_sp));//XXX breaks compatibility with multiple setpoints
+
+ if (mavlink_system.sysid == local_ned_position_setpoint_external.target_system &&
+ mavlink_system.compid == local_ned_position_setpoint_external.target_component) {
+
+ /* convert mavlink type (local, NED) to uORB offboard control struct */
+ switch (local_ned_position_setpoint_external.coordinate_frame) {
+ case MAV_FRAME_LOCAL_NED:
+ offboard_control_sp.mode = OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_NED;
+ break;
+ case MAV_FRAME_LOCAL_OFFSET_NED:
+ offboard_control_sp.mode = OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_OFFSET_NED;
+ break;
+ case MAV_FRAME_BODY_NED:
+ offboard_control_sp.mode = OFFBOARD_CONTROL_MODE_DIRECT_BODY_NED;
+ break;
+ case MAV_FRAME_BODY_OFFSET_NED:
+ offboard_control_sp.mode = OFFBOARD_CONTROL_MODE_DIRECT_BODY_OFFSET_NED;
+ break;
+ default:
+ /* invalid setpoint, avoid publishing */
+ return;
+ }
+ offboard_control_sp.position[0] = local_ned_position_setpoint_external.x;
+ offboard_control_sp.position[1] = local_ned_position_setpoint_external.y;
+ offboard_control_sp.position[2] = local_ned_position_setpoint_external.z;
+ offboard_control_sp.velocity[0] = local_ned_position_setpoint_external.vx;
+ offboard_control_sp.velocity[1] = local_ned_position_setpoint_external.vy;
+ offboard_control_sp.velocity[2] = local_ned_position_setpoint_external.vz;
+ offboard_control_sp.acceleration[0] = local_ned_position_setpoint_external.afx;
+ offboard_control_sp.acceleration[1] = local_ned_position_setpoint_external.afy;
+ offboard_control_sp.acceleration[2] = local_ned_position_setpoint_external.afz;
+ offboard_control_sp.isForceSetpoint = (bool)(local_ned_position_setpoint_external.type_mask & (1 << 9));
+ for (int i = 0; i < 9; i++) {
+ offboard_control_sp.ignore &= ~(1 << i);
+ offboard_control_sp.ignore |= (local_ned_position_setpoint_external.type_mask & (1 << i));
+ }
+
+
+ offboard_control_sp.timestamp = hrt_absolute_time();
+
+ if (_offboard_control_sp_pub < 0) {
+ _offboard_control_sp_pub = orb_advertise(ORB_ID(offboard_control_setpoint), &offboard_control_sp);
+
+ } else {
+ orb_publish(ORB_ID(offboard_control_setpoint), _offboard_control_sp_pub, &offboard_control_sp);
+ }
+
+ /* If we are in offboard control mode and offboard control loop through is enabled
+ * also publish the setpoint topic which is read by the controller */
+ if (_mavlink->get_forward_externalsp()) {
+ bool updated;
+ orb_check(_control_mode_sub, &updated);
+ if (updated) {
+ orb_copy(ORB_ID(vehicle_control_mode), _control_mode_sub, &_control_mode);
+ }
+
+ if (_control_mode.flag_control_offboard_enabled) {
+ //XXX: copy to and publish setpoint triplet here
+ }
+
+ }
+ }
+}
+
+void
+MavlinkReceiver::handle_message_attitude_setpoint_external(mavlink_message_t *msg)
+{
+ mavlink_attitude_setpoint_external_t attitude_setpoint_external;
+ mavlink_msg_attitude_setpoint_external_decode(msg, &attitude_setpoint_external);
+
+ struct offboard_control_setpoint_s offboard_control_sp;
+ memset(&offboard_control_sp, 0, sizeof(offboard_control_sp)); //XXX breaks compatibility with multiple setpoints
+
+ if (mavlink_system.sysid == attitude_setpoint_external.target_system &&
+ mavlink_system.compid == attitude_setpoint_external.target_component) {
+ for (int i = 0; i < 4; i++) {
+ offboard_control_sp.attitude[i] = attitude_setpoint_external.q[i];
+ }
+ offboard_control_sp.attitude_rate[0] = attitude_setpoint_external.body_roll_rate;
+ offboard_control_sp.attitude_rate[1] = attitude_setpoint_external.body_pitch_rate;
+ offboard_control_sp.attitude_rate[2] = attitude_setpoint_external.body_yaw_rate;
+
+ for (int i = 0; i < 3; i++) {
+ offboard_control_sp.ignore &= ~(1 << (i + 9));
+ offboard_control_sp.ignore |= (attitude_setpoint_external.type_mask & (1 << i)) << 9;
+ }
+ offboard_control_sp.ignore &= ~(1 << 10);
+ offboard_control_sp.ignore |= ((attitude_setpoint_external.type_mask & (1 << 7)) << 3);
+
+
+ offboard_control_sp.timestamp = hrt_absolute_time();
+
+ if (_offboard_control_sp_pub < 0) {
+ _offboard_control_sp_pub = orb_advertise(ORB_ID(offboard_control_setpoint), &offboard_control_sp);
+
+ } else {
+ orb_publish(ORB_ID(offboard_control_setpoint), _offboard_control_sp_pub, &offboard_control_sp);
+ }
+
+ /* If we are in offboard control mode and offboard control loop through is enabled
+ * also publish the setpoint topic which is read by the controller */
+ if (_mavlink->get_forward_externalsp()) {
+ bool updated;
+ orb_check(_control_mode_sub, &updated);
+ if (updated) {
+ orb_copy(ORB_ID(vehicle_control_mode), _control_mode_sub, &_control_mode);
+ }
+
+ if (_control_mode.flag_control_offboard_enabled) {
+
+ /* Publish attitude setpoint if ignore bit is not set */
+ if (!(attitude_setpoint_external.type_mask & (1 << 7))) {
+ struct vehicle_attitude_setpoint_s att_sp;
+ mavlink_quaternion_to_euler(attitude_setpoint_external.q,
+ &att_sp.roll_body, &att_sp.pitch_body, &att_sp.yaw_body);
+ att_sp.thrust = attitude_setpoint_external.thrust;
+ if (_att_sp_pub < 0) {
+ _att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &att_sp);
+ } else {
+ orb_publish(ORB_ID(vehicle_attitude_setpoint), _att_sp_pub, &att_sp);
+ }
+ }
+
+ /* Publish attitude rate setpoint if ignore bit are not set */
+ ///XXX add support for ignoring individual axes
+ if (!(attitude_setpoint_external.type_mask & (0b111))) {
+ struct vehicle_rates_setpoint_s rates_sp;
+ rates_sp.roll = attitude_setpoint_external.body_roll_rate;
+ rates_sp.pitch = attitude_setpoint_external.body_pitch_rate;
+ rates_sp.yaw = attitude_setpoint_external.body_yaw_rate;
+ rates_sp.thrust = attitude_setpoint_external.thrust;
+
+ if (_att_sp_pub < 0) {
+ _rates_sp_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &rates_sp);
+ } else {
+ orb_publish(ORB_ID(vehicle_rates_setpoint), _rates_sp_pub, &rates_sp);
+ }
+ }
+ }
+
+ }
+ }
+}
+
+void
MavlinkReceiver::handle_message_radio_status(mavlink_message_t *msg)
{
/* telemetry status supported only on first TELEMETRY_STATUS_ORB_ID_NUM mavlink channels */
diff --git a/src/modules/mavlink/mavlink_receiver.h b/src/modules/mavlink/mavlink_receiver.h
index 8d38b9973..0f12cf32c 100644
--- a/src/modules/mavlink/mavlink_receiver.h
+++ b/src/modules/mavlink/mavlink_receiver.h
@@ -113,6 +113,8 @@ private:
void handle_message_set_mode(mavlink_message_t *msg);
void handle_message_vicon_position_estimate(mavlink_message_t *msg);
void handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message_t *msg);
+ void handle_message_local_ned_position_setpoint_external(mavlink_message_t *msg);
+ void handle_message_attitude_setpoint_external(mavlink_message_t *msg);
void handle_message_radio_status(mavlink_message_t *msg);
void handle_message_manual_control(mavlink_message_t *msg);
void handle_message_heartbeat(mavlink_message_t *msg);
diff --git a/src/modules/navigator/offboard.cpp b/src/modules/navigator/offboard.cpp
index dcb5c6000..fc4d183cd 100644
--- a/src/modules/navigator/offboard.cpp
+++ b/src/modules/navigator/offboard.cpp
@@ -68,11 +68,6 @@ Offboard::~Offboard()
}
void
-Offboard::on_inactive()
-{
-}
-
-void
Offboard::on_activation()
{
}
@@ -89,37 +84,55 @@ Offboard::on_active()
}
/* copy offboard setpoints to the corresponding topics */
- if (_navigator->get_control_mode()->flag_control_position_enabled
- && _offboard_control_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_POSITION) {
- /* position control */
- pos_sp_triplet->current.x = _offboard_control_sp.p1;
- pos_sp_triplet->current.y = _offboard_control_sp.p2;
- pos_sp_triplet->current.yaw = _offboard_control_sp.p3;
- pos_sp_triplet->current.z = -_offboard_control_sp.p4;
-
- pos_sp_triplet->current.type = SETPOINT_TYPE_OFFBOARD;
- pos_sp_triplet->current.valid = true;
- pos_sp_triplet->current.position_valid = true;
-
- _navigator->set_position_setpoint_triplet_updated();
-
- } else if (_navigator->get_control_mode()->flag_control_velocity_enabled
- && _offboard_control_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY) {
- /* velocity control */
- pos_sp_triplet->current.vx = _offboard_control_sp.p2;
- pos_sp_triplet->current.vy = _offboard_control_sp.p1;
- pos_sp_triplet->current.yawspeed = _offboard_control_sp.p3;
- pos_sp_triplet->current.vz = _offboard_control_sp.p4;
-
- pos_sp_triplet->current.type = SETPOINT_TYPE_OFFBOARD;
- pos_sp_triplet->current.valid = true;
- pos_sp_triplet->current.velocity_valid = true;
-
- _navigator->set_position_setpoint_triplet_updated();
+ if (_offboard_control_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_NED) {
+ /* We accept position control only if none of the directions is ignored (as pos_sp_triplet does not
+ * support deactivation of individual directions) */
+ if (_navigator->get_control_mode()->flag_control_position_enabled &&
+ (!offboard_control_sp_ignore_position(_offboard_control_sp, 0) &&
+ !offboard_control_sp_ignore_position(_offboard_control_sp, 1) &&
+ !offboard_control_sp_ignore_position(_offboard_control_sp, 2))) {
+ /* position control */
+ pos_sp_triplet->current.x = _offboard_control_sp.position[0];
+ pos_sp_triplet->current.y = _offboard_control_sp.position[1];
+ //pos_sp_triplet->current.yaw = _offboard_control_sp.position[2];
+ //XXX: copy yaw
+ pos_sp_triplet->current.z = -_offboard_control_sp.position[2];
+
+ pos_sp_triplet->current.type = SETPOINT_TYPE_OFFBOARD;
+ pos_sp_triplet->current.valid = true;
+ pos_sp_triplet->current.position_valid = true;
+
+ _navigator->set_position_setpoint_triplet_updated();
+ }
+ /* We accept velocity control only if none of the directions is ignored (as pos_sp_triplet does not
+ * support deactivation of individual directions) */
+ if (_navigator->get_control_mode()->flag_control_velocity_enabled &&
+ (!offboard_control_sp_ignore_velocity(_offboard_control_sp, 0) &&
+ !offboard_control_sp_ignore_velocity(_offboard_control_sp, 1) &&
+ !offboard_control_sp_ignore_velocity(_offboard_control_sp, 2))) {
+ /* velocity control */
+ pos_sp_triplet->current.vx = _offboard_control_sp.velocity[0];
+ pos_sp_triplet->current.vy = _offboard_control_sp.velocity[1];
+// pos_sp_triplet->current.yawspeed = _offboard_control_sp.velocity[;
+// //XXX: copy yaw speed
+ pos_sp_triplet->current.vz = _offboard_control_sp.velocity[2];
+
+ pos_sp_triplet->current.type = SETPOINT_TYPE_OFFBOARD;
+ pos_sp_triplet->current.valid = true;
+ pos_sp_triplet->current.velocity_valid = true;
+
+ _navigator->set_position_setpoint_triplet_updated();
+ }
+
+ //XXX: map acceleration setpoint once supported in setpoint triplet
}
}
+void
+Offboard::on_inactive()
+{
+}
void
Offboard::update_offboard_control_setpoint()
diff --git a/src/modules/uORB/topics/offboard_control_setpoint.h b/src/modules/uORB/topics/offboard_control_setpoint.h
index d7b131e3c..809a2ace4 100644
--- a/src/modules/uORB/topics/offboard_control_setpoint.h
+++ b/src/modules/uORB/topics/offboard_control_setpoint.h
@@ -53,11 +53,22 @@ enum OFFBOARD_CONTROL_MODE {
OFFBOARD_CONTROL_MODE_DIRECT = 0,
OFFBOARD_CONTROL_MODE_DIRECT_RATES = 1,
OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE = 2,
- OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY = 3,
- OFFBOARD_CONTROL_MODE_DIRECT_POSITION = 4,
- OFFBOARD_CONTROL_MODE_ATT_YAW_RATE = 5,
- OFFBOARD_CONTROL_MODE_ATT_YAW_POS = 6,
- OFFBOARD_CONTROL_MODE_MULTIROTOR_SIMPLE = 7, /**< roll / pitch rotated aligned to the takeoff orientation, throttle stabilized, yaw pos */
+ OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_NED = 3,
+ OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_OFFSET_NED = 4,
+ OFFBOARD_CONTROL_MODE_DIRECT_BODY_NED = 5,
+ OFFBOARD_CONTROL_MODE_DIRECT_BODY_OFFSET_NED = 6,
+ OFFBOARD_CONTROL_MODE_DIRECT_GLOBAL = 7,
+ OFFBOARD_CONTROL_MODE_ATT_YAW_RATE = 8,
+ OFFBOARD_CONTROL_MODE_ATT_YAW_POS = 9,
+ OFFBOARD_CONTROL_MODE_MULTIROTOR_SIMPLE = 10, /**< roll / pitch rotated aligned to the takeoff orientation, throttle stabilized, yaw pos */
+};
+
+enum OFFBOARD_CONTROL_FRAME {
+ OFFBOARD_CONTROL_FRAME_LOCAL_NED = 0,
+ OFFBOARD_CONTROL_FRAME_LOCAL_OFFSET_NED = 1,
+ OFFBOARD_CONTROL_FRAME_BODY_NED = 2,
+ OFFBOARD_CONTROL_FRAME_BODY_OFFSET_NED = 3,
+ OFFBOARD_CONTROL_FRAME_GLOBAL = 4
};
/**
@@ -70,10 +81,15 @@ struct offboard_control_setpoint_s {
enum OFFBOARD_CONTROL_MODE mode; /**< The current control inputs mode */
- float p1; /**< ailerons roll / roll rate input */
- float p2; /**< elevator / pitch / pitch rate */
- float p3; /**< rudder / yaw rate / yaw */
- float p4; /**< throttle / collective thrust / altitude */
+ double position[3]; /**< lat, lon, alt / x, y, z */
+ float velocity[3]; /**< x vel, y vel, z vel */
+ float acceleration[3]; /**< x acc, y acc, z acc */
+ float attitude[4]; /**< attitude of vehicle (quaternion) */
+ float attitude_rate[3]; /**< body angular rates (x, y, z) */
+
+ uint16_t ignore; /**< if field i is set to true, pi should be ignored */
+ //XXX define constants for bit offsets
+ bool isForceSetpoint; /**< the acceleration vector should be interpreted as force */
float override_mode_switch;
@@ -87,6 +103,27 @@ struct offboard_control_setpoint_s {
* @}
*/
+inline bool offboard_control_sp_ignore_position(const struct offboard_control_setpoint_s &offboard_control_sp, int index) {
+ return (bool)(offboard_control_sp.ignore & (1 << index));
+}
+
+inline bool offboard_control_sp_ignore_velocity(const struct offboard_control_setpoint_s &offboard_control_sp, int index) {
+ return (bool)(offboard_control_sp.ignore & (1 << (3 + index)));
+}
+
+inline bool offboard_control_sp_ignore_acceleration(const struct offboard_control_setpoint_s &offboard_control_sp, int index) {
+ return (bool)(offboard_control_sp.ignore & (1 << (6 + index)));
+}
+
+inline bool offboard_control_sp_ignore_bodyrates(const struct offboard_control_setpoint_s &offboard_control_sp, int index) {
+ return (bool)(offboard_control_sp.ignore & (1 << (9 + index)));
+}
+
+inline bool offboard_control_sp_ignore_attitude(const struct offboard_control_setpoint_s &offboard_control_sp) {
+ return (bool)(offboard_control_sp.ignore & (1 << 10));
+}
+
+
/* register this as object request broker structure */
ORB_DECLARE(offboard_control_setpoint);
diff --git a/src/modules/uORB/topics/vehicle_command.h b/src/modules/uORB/topics/vehicle_command.h
index c21a29b13..faf8cc7db 100644
--- a/src/modules/uORB/topics/vehicle_command.h
+++ b/src/modules/uORB/topics/vehicle_command.h
@@ -61,6 +61,9 @@ enum VEHICLE_CMD {
VEHICLE_CMD_NAV_TAKEOFF = 22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */
VEHICLE_CMD_NAV_ROI = 80, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */
VEHICLE_CMD_NAV_PATHPLANNING = 81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */
+ VEHICLE_CMD_NAV_GUIDED_LIMITS=90, /* set limits for external control |timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout| absolute altitude min (in meters, WGS84) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit| absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit| horizontal move limit (in meters, WGS84) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit| Empty| Empty| Empty| */
+ VEHICLE_CMD_NAV_GUIDED_MASTER=91, /* set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty| */
+ VEHICLE_CMD_NAV_GUIDED_ENABLE=92, /* hand control over to an external controller |On / Off (> 0.5f on)| Empty| Empty| Empty| Empty| Empty| Empty| */
VEHICLE_CMD_NAV_LAST = 95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
VEHICLE_CMD_CONDITION_DELAY = 112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */
VEHICLE_CMD_CONDITION_CHANGE_ALT = 113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */