aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--ROMFS/px4fmu_common/init.d/3035_viper10
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.autostart5
-rwxr-xr-xROMFS/px4fmu_common/mixers/FMU_FX79.mix4
-rwxr-xr-xROMFS/px4fmu_common/mixers/Viper.mix72
m---------mavlink/include/mavlink/v1.00
-rw-r--r--src/modules/ekf_att_pos_estimator/estimator_23states.cpp31
-rw-r--r--src/modules/mavlink/mavlink_messages.cpp152
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp34
-rw-r--r--src/modules/mc_pos_control/mc_pos_control_main.cpp283
-rw-r--r--src/modules/uORB/topics/position_setpoint_triplet.h8
-rw-r--r--src/modules/uORB/topics/vehicle_local_position_setpoint.h3
11 files changed, 318 insertions, 284 deletions
diff --git a/ROMFS/px4fmu_common/init.d/3035_viper b/ROMFS/px4fmu_common/init.d/3035_viper
new file mode 100644
index 000000000..a4c1e832d
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/3035_viper
@@ -0,0 +1,10 @@
+#!nsh
+#
+# Viper
+#
+# Simon Wilks <sjwilks@gmail.com>
+#
+
+sh /etc/init.d/rc.fw_defaults
+
+set MIXER Viper
diff --git a/ROMFS/px4fmu_common/init.d/rc.autostart b/ROMFS/px4fmu_common/init.d/rc.autostart
index 17541e680..9de7d9ecd 100644
--- a/ROMFS/px4fmu_common/init.d/rc.autostart
+++ b/ROMFS/px4fmu_common/init.d/rc.autostart
@@ -103,6 +103,11 @@ then
sh /etc/init.d/3034_fx79
fi
+if param compare SYS_AUTOSTART 3035 35
+then
+ sh /etc/init.d/3035_viper
+fi
+
if param compare SYS_AUTOSTART 3100
then
sh /etc/init.d/3100_tbs_caipirinha
diff --git a/ROMFS/px4fmu_common/mixers/FMU_FX79.mix b/ROMFS/px4fmu_common/mixers/FMU_FX79.mix
index 0a1dca98d..112d9b891 100755
--- a/ROMFS/px4fmu_common/mixers/FMU_FX79.mix
+++ b/ROMFS/px4fmu_common/mixers/FMU_FX79.mix
@@ -27,12 +27,12 @@ for the elevons.
M: 2
O: 10000 10000 0 -10000 10000
-S: 0 0 5000 8000 0 -10000 10000
+S: 0 0 7500 7500 0 -10000 10000
S: 0 1 8000 8000 0 -10000 10000
M: 2
O: 10000 10000 0 -10000 10000
-S: 0 0 8000 5000 0 -10000 10000
+S: 0 0 7500 7500 0 -10000 10000
S: 0 1 -8000 -8000 0 -10000 10000
Output 2
diff --git a/ROMFS/px4fmu_common/mixers/Viper.mix b/ROMFS/px4fmu_common/mixers/Viper.mix
new file mode 100755
index 000000000..79c4447be
--- /dev/null
+++ b/ROMFS/px4fmu_common/mixers/Viper.mix
@@ -0,0 +1,72 @@
+Viper Delta-wing mixer
+=================================
+
+Designed for Viper.
+
+TODO (sjwilks): Add mixers for flaps.
+
+This file defines mixers suitable for controlling a delta wing aircraft using
+PX4FMU. The configuration assumes the elevon servos are connected to PX4FMU
+servo outputs 0 and 1 and the motor speed control to output 3. Output 2 is
+assumed to be unused.
+
+Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
+(roll), 1 (pitch) and 3 (thrust).
+
+See the README for more information on the scaler format.
+
+Elevon mixers
+-------------
+Three scalers total (output, roll, pitch).
+
+On the assumption that the two elevon servos are physically reversed, the pitch
+input is inverted between the two servos.
+
+The scaling factor for roll inputs is adjusted to implement differential travel
+for the elevons.
+
+M: 2
+O: 10000 10000 0 -10000 10000
+S: 0 0 7500 7500 0 -10000 10000
+S: 0 1 8000 8000 0 -10000 10000
+
+M: 2
+O: 10000 10000 0 -10000 10000
+S: 0 0 7500 7500 0 -10000 10000
+S: 0 1 -8000 -8000 0 -10000 10000
+
+Output 2
+--------
+This mixer is empty.
+
+Z:
+
+Motor speed mixer
+-----------------
+Two scalers total (output, thrust).
+
+This mixer generates a full-range output (-1 to 1) from an input in the (0 - 1)
+range. Inputs below zero are treated as zero.
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 3 0 20000 -10000 -10000 10000
+
+Gimbal / flaps / payload mixer for last four channels
+-----------------------------------------------------
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 4 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 5 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 6 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 7 10000 10000 0 -10000 10000
diff --git a/mavlink/include/mavlink/v1.0 b/mavlink/include/mavlink/v1.0
-Subproject 04b1ad5b284d5e916858ca9f928e93d97bbf6ad
+Subproject 4cd384001b5373e1ecaa6c4cd66994855cec474
diff --git a/src/modules/ekf_att_pos_estimator/estimator_23states.cpp b/src/modules/ekf_att_pos_estimator/estimator_23states.cpp
index ffdd29a5b..c7c7305b2 100644
--- a/src/modules/ekf_att_pos_estimator/estimator_23states.cpp
+++ b/src/modules/ekf_att_pos_estimator/estimator_23states.cpp
@@ -1032,10 +1032,16 @@ void AttPosEKF::FuseVelposNED()
// apply a 5-sigma threshold
current_ekf_state.velHealth = (sq(velInnov[0]) + sq(velInnov[1]) + sq(velInnov[2])) < 25.0f * (varInnovVelPos[0] + varInnovVelPos[1] + varInnovVelPos[2]);
current_ekf_state.velTimeout = (millis() - current_ekf_state.velFailTime) > horizRetryTime;
- if (current_ekf_state.velHealth || current_ekf_state.velTimeout)
- {
+ if (current_ekf_state.velHealth || staticMode) {
current_ekf_state.velHealth = true;
current_ekf_state.velFailTime = millis();
+ } else if (current_ekf_state.velTimeout || !current_ekf_state.posHealth) {
+ // XXX check
+ current_ekf_state.velHealth = true;
+ ResetVelocity();
+ ResetStoredStates();
+ // do not fuse bad data
+ fuseVelData = false;
}
else
{
@@ -1056,6 +1062,17 @@ void AttPosEKF::FuseVelposNED()
{
current_ekf_state.posHealth = true;
current_ekf_state.posFailTime = millis();
+
+ if (current_ekf_state.posTimeout) {
+ ResetPosition();
+
+ // XXX cross-check the state reset
+ ResetStoredStates();
+
+ // do not fuse position data on this time
+ // step
+ fusePosData = false;
+ }
}
else
{
@@ -1070,10 +1087,18 @@ void AttPosEKF::FuseVelposNED()
// apply a 10-sigma threshold
current_ekf_state.hgtHealth = sq(hgtInnov) < 100.0f*varInnovVelPos[5];
current_ekf_state.hgtTimeout = (millis() - current_ekf_state.hgtFailTime) > hgtRetryTime;
- if (current_ekf_state.hgtHealth || current_ekf_state.hgtTimeout)
+ if (current_ekf_state.hgtHealth || current_ekf_state.hgtTimeout || staticMode)
{
current_ekf_state.hgtHealth = true;
current_ekf_state.hgtFailTime = millis();
+
+ // if we just reset from a timeout, do not fuse
+ // the height data, but reset height and stored states
+ if (current_ekf_state.hgtTimeout) {
+ ResetHeight();
+ ResetStoredStates();
+ fuseHgtData = false;
+ }
}
else
{
diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp
index 683f0f1e8..c10be77b5 100644
--- a/src/modules/mavlink/mavlink_messages.cpp
+++ b/src/modules/mavlink/mavlink_messages.cpp
@@ -1385,43 +1385,43 @@ protected:
};
-class MavlinkStreamGlobalPositionSetpointInt : public MavlinkStream
+class MavlinkStreamPositionTargetGlobalInt : public MavlinkStream
{
public:
const char *get_name() const
{
- return MavlinkStreamGlobalPositionSetpointInt::get_name_static();
+ return MavlinkStreamPositionTargetGlobalInt::get_name_static();
}
static const char *get_name_static()
{
- return "GLOBAL_POSITION_SETPOINT_INT";
+ return "POSITION_TARGET_GLOBAL_INT";
}
uint8_t get_id()
{
- return MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT;
+ return MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT;
}
static MavlinkStream *new_instance(Mavlink *mavlink)
{
- return new MavlinkStreamGlobalPositionSetpointInt(mavlink);
+ return new MavlinkStreamPositionTargetGlobalInt(mavlink);
}
unsigned get_size()
{
- return MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
+ return MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
}
private:
MavlinkOrbSubscription *_pos_sp_triplet_sub;
/* do not allow top copying this class */
- MavlinkStreamGlobalPositionSetpointInt(MavlinkStreamGlobalPositionSetpointInt &);
- MavlinkStreamGlobalPositionSetpointInt& operator = (const MavlinkStreamGlobalPositionSetpointInt &);
+ MavlinkStreamPositionTargetGlobalInt(MavlinkStreamPositionTargetGlobalInt &);
+ MavlinkStreamPositionTargetGlobalInt& operator = (const MavlinkStreamPositionTargetGlobalInt &);
protected:
- explicit MavlinkStreamGlobalPositionSetpointInt(Mavlink *mavlink) : MavlinkStream(mavlink),
+ explicit MavlinkStreamPositionTargetGlobalInt(Mavlink *mavlink) : MavlinkStream(mavlink),
_pos_sp_triplet_sub(_mavlink->add_orb_subscription(ORB_ID(position_setpoint_triplet)))
{}
@@ -1430,15 +1430,14 @@ protected:
struct position_setpoint_triplet_s pos_sp_triplet;
if (_pos_sp_triplet_sub->update(&pos_sp_triplet)) {
- mavlink_global_position_setpoint_int_t msg;
+ mavlink_position_target_global_int_t msg{};
msg.coordinate_frame = MAV_FRAME_GLOBAL;
- msg.latitude = pos_sp_triplet.current.lat * 1e7;
- msg.longitude = pos_sp_triplet.current.lon * 1e7;
- msg.altitude = pos_sp_triplet.current.alt * 1000;
- msg.yaw = pos_sp_triplet.current.yaw * M_RAD_TO_DEG_F * 100.0f;
+ msg.lat_int = pos_sp_triplet.current.lat * 1e7;
+ msg.lon_int = pos_sp_triplet.current.lon * 1e7;
+ msg.alt = pos_sp_triplet.current.alt;
- _mavlink->send_message(MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, &msg);
+ _mavlink->send_message(MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, &msg);
}
}
};
@@ -1454,12 +1453,12 @@ public:
static const char *get_name_static()
{
- return "LOCAL_POSITION_SETPOINT";
+ return "POSITION_TARGET_LOCAL_NED";
}
uint8_t get_id()
{
- return MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT;
+ return MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED;
}
static MavlinkStream *new_instance(Mavlink *mavlink)
@@ -1469,7 +1468,7 @@ public:
unsigned get_size()
{
- return MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
+ return MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
}
private:
@@ -1491,137 +1490,87 @@ protected:
struct vehicle_local_position_setpoint_s pos_sp;
if (_pos_sp_sub->update(&_pos_sp_time, &pos_sp)) {
- mavlink_local_position_setpoint_t msg;
+ mavlink_position_target_local_ned_t msg{};
+ msg.time_boot_ms = pos_sp.timestamp / 1000;
msg.coordinate_frame = MAV_FRAME_LOCAL_NED;
msg.x = pos_sp.x;
msg.y = pos_sp.y;
msg.z = pos_sp.z;
- msg.yaw = pos_sp.yaw;
- _mavlink->send_message(MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, &msg);
+ _mavlink->send_message(MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, &msg);
}
}
};
-class MavlinkStreamRollPitchYawThrustSetpoint : public MavlinkStream
+class MavlinkStreamAttitudeTarget : public MavlinkStream
{
public:
const char *get_name() const
{
- return MavlinkStreamRollPitchYawThrustSetpoint::get_name_static();
+ return MavlinkStreamAttitudeTarget::get_name_static();
}
static const char *get_name_static()
{
- return "ROLL_PITCH_YAW_THRUST_SETPOINT";
+ return "ATTITUDE_TARGET";
}
uint8_t get_id()
{
- return MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT;
+ return MAVLINK_MSG_ID_ATTITUDE_TARGET;
}
static MavlinkStream *new_instance(Mavlink *mavlink)
{
- return new MavlinkStreamRollPitchYawThrustSetpoint(mavlink);
+ return new MavlinkStreamAttitudeTarget(mavlink);
}
unsigned get_size()
{
- return MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
+ return MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
}
private:
- MavlinkOrbSubscription *att_sp_sub;
- uint64_t att_sp_time;
+ MavlinkOrbSubscription *_att_sp_sub;
+ MavlinkOrbSubscription *_att_rates_sp_sub;
+ uint64_t _att_sp_time;
+ uint64_t _att_rates_sp_time;
/* do not allow top copying this class */
- MavlinkStreamRollPitchYawThrustSetpoint(MavlinkStreamRollPitchYawThrustSetpoint &);
- MavlinkStreamRollPitchYawThrustSetpoint& operator = (const MavlinkStreamRollPitchYawThrustSetpoint &);
+ MavlinkStreamAttitudeTarget(MavlinkStreamAttitudeTarget &);
+ MavlinkStreamAttitudeTarget& operator = (const MavlinkStreamAttitudeTarget &);
protected:
- explicit MavlinkStreamRollPitchYawThrustSetpoint(Mavlink *mavlink) : MavlinkStream(mavlink),
- att_sp_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_attitude_setpoint))),
- att_sp_time(0)
+ explicit MavlinkStreamAttitudeTarget(Mavlink *mavlink) : MavlinkStream(mavlink),
+ _att_sp_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_attitude_setpoint))),
+ _att_rates_sp_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_rates_setpoint))),
+ _att_sp_time(0),
+ _att_rates_sp_time(0)
{}
void send(const hrt_abstime t)
{
struct vehicle_attitude_setpoint_s att_sp;
- if (att_sp_sub->update(&att_sp_time, &att_sp)) {
- mavlink_roll_pitch_yaw_thrust_setpoint_t msg;
-
- msg.time_boot_ms = att_sp.timestamp / 1000;
- msg.roll = att_sp.roll_body;
- msg.pitch = att_sp.pitch_body;
- msg.yaw = att_sp.yaw_body;
- msg.thrust = att_sp.thrust;
-
- _mavlink->send_message(MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, &msg);
- }
- }
-};
-
+ if (_att_sp_sub->update(&_att_sp_time, &att_sp)) {
-class MavlinkStreamRollPitchYawRatesThrustSetpoint : public MavlinkStream
-{
-public:
- const char *get_name() const
- {
- return MavlinkStreamRollPitchYawRatesThrustSetpoint::get_name_static();
- }
-
- static const char *get_name_static()
- {
- return "ROLL_PITCH_YAW_RATES_THRUST_SETPOINT";
- }
+ struct vehicle_rates_setpoint_s att_rates_sp;
+ (void)_att_rates_sp_sub->update(&_att_rates_sp_time, &att_rates_sp);
- uint8_t get_id()
- {
- return MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT;
- }
+ mavlink_attitude_target_t msg{};
- static MavlinkStream *new_instance(Mavlink *mavlink)
- {
- return new MavlinkStreamRollPitchYawRatesThrustSetpoint(mavlink);
- }
-
- unsigned get_size()
- {
- return MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
- }
-
-private:
- MavlinkOrbSubscription *_att_rates_sp_sub;
- uint64_t _att_rates_sp_time;
-
- /* do not allow top copying this class */
- MavlinkStreamRollPitchYawRatesThrustSetpoint(MavlinkStreamRollPitchYawRatesThrustSetpoint &);
- MavlinkStreamRollPitchYawRatesThrustSetpoint& operator = (const MavlinkStreamRollPitchYawRatesThrustSetpoint &);
-
-protected:
- explicit MavlinkStreamRollPitchYawRatesThrustSetpoint(Mavlink *mavlink) : MavlinkStream(mavlink),
- _att_rates_sp_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_rates_setpoint))),
- _att_rates_sp_time(0)
- {}
-
- void send(const hrt_abstime t)
- {
- struct vehicle_rates_setpoint_s att_rates_sp;
+ msg.time_boot_ms = att_sp.timestamp / 1000;
+ mavlink_euler_to_quaternion(att_sp.roll_body, att_sp.pitch_body, att_sp.yaw_body, msg.q);
- if (_att_rates_sp_sub->update(&_att_rates_sp_time, &att_rates_sp)) {
- mavlink_roll_pitch_yaw_rates_thrust_setpoint_t msg;
+ msg.body_roll_rate = att_rates_sp.roll;
+ msg.body_pitch_rate = att_rates_sp.pitch;
+ msg.body_yaw_rate = att_rates_sp.yaw;
- msg.time_boot_ms = att_rates_sp.timestamp / 1000;
- msg.roll_rate = att_rates_sp.roll;
- msg.pitch_rate = att_rates_sp.pitch;
- msg.yaw_rate = att_rates_sp.yaw;
- msg.thrust = att_rates_sp.thrust;
+ msg.thrust = att_sp.thrust;
- _mavlink->send_message(MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, &msg);
+ _mavlink->send_message(MAVLINK_MSG_ID_ATTITUDE_TARGET, &msg);
}
}
};
@@ -2149,10 +2098,9 @@ StreamListItem *streams_list[] = {
new StreamListItem(&MavlinkStreamServoOutputRaw<2>::new_instance, &MavlinkStreamServoOutputRaw<2>::get_name_static),
new StreamListItem(&MavlinkStreamServoOutputRaw<3>::new_instance, &MavlinkStreamServoOutputRaw<3>::get_name_static),
new StreamListItem(&MavlinkStreamHILControls::new_instance, &MavlinkStreamHILControls::get_name_static),
- new StreamListItem(&MavlinkStreamGlobalPositionSetpointInt::new_instance, &MavlinkStreamGlobalPositionSetpointInt::get_name_static),
+ new StreamListItem(&MavlinkStreamPositionTargetGlobalInt::new_instance, &MavlinkStreamPositionTargetGlobalInt::get_name_static),
new StreamListItem(&MavlinkStreamLocalPositionSetpoint::new_instance, &MavlinkStreamLocalPositionSetpoint::get_name_static),
- new StreamListItem(&MavlinkStreamRollPitchYawThrustSetpoint::new_instance, &MavlinkStreamRollPitchYawThrustSetpoint::get_name_static),
- new StreamListItem(&MavlinkStreamRollPitchYawRatesThrustSetpoint::new_instance, &MavlinkStreamRollPitchYawRatesThrustSetpoint::get_name_static),
+ new StreamListItem(&MavlinkStreamAttitudeTarget::new_instance, &MavlinkStreamAttitudeTarget::get_name_static),
new StreamListItem(&MavlinkStreamRCChannelsRaw::new_instance, &MavlinkStreamRCChannelsRaw::get_name_static),
new StreamListItem(&MavlinkStreamManualControl::new_instance, &MavlinkStreamManualControl::get_name_static),
new StreamListItem(&MavlinkStreamOpticalFlow::new_instance, &MavlinkStreamOpticalFlow::get_name_static),
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index 69e3ef31d..63bac45c0 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -148,10 +148,6 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
handle_message_vicon_position_estimate(msg);
break;
- case MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST:
- handle_message_quad_swarm_roll_pitch_yaw_thrust(msg);
- break;
-
case MAVLINK_MSG_ID_RADIO_STATUS:
handle_message_radio_status(msg);
break;
@@ -363,36 +359,6 @@ MavlinkReceiver::handle_message_vicon_position_estimate(mavlink_message_t *msg)
}
void
-MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message_t *msg)
-{
- mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t swarm_offboard_control;
- mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(msg, &swarm_offboard_control);
-
- /* Only accept system IDs from 1 to 4 */
- if (mavlink_system.sysid >= 1 && mavlink_system.sysid <= 4) {
- struct offboard_control_setpoint_s offboard_control_sp;
- 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;
-
- offboard_control_sp.mode = (enum OFFBOARD_CONTROL_MODE)swarm_offboard_control.mode;
-
- 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);
- }
- }
-}
-
-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/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp
index 9b0f69226..ecc40428d 100644
--- a/src/modules/mc_pos_control/mc_pos_control_main.cpp
+++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp
@@ -105,6 +105,7 @@ public:
int start();
private:
+ const float alt_ctl_dz = 0.2f;
bool _task_should_exit; /**< if true, task should exit */
int _control_task; /**< task handle for task */
@@ -184,6 +185,8 @@ private:
math::Vector<3> _vel;
math::Vector<3> _vel_sp;
math::Vector<3> _vel_prev; /**< velocity on previous step */
+ math::Vector<3> _vel_ff;
+ math::Vector<3> _sp_move_rate;
/**
* Update our local parameter cache.
@@ -217,6 +220,16 @@ private:
void reset_alt_sp();
/**
+ * Set position setpoint using manual control
+ */
+ void control_manual(float dt);
+
+ /**
+ * Set position setpoint using offboard control
+ */
+ void control_offboard(float dt);
+
+ /**
* Select between barometric and global (AMSL) altitudes
*/
void select_alt(bool global);
@@ -297,6 +310,8 @@ MulticopterPositionControl::MulticopterPositionControl() :
_vel.zero();
_vel_sp.zero();
_vel_prev.zero();
+ _vel_ff.zero();
+ _sp_move_rate.zero();
_params_handles.thr_min = param_find("MPC_THR_MIN");
_params_handles.thr_max = param_find("MPC_THR_MAX");
@@ -392,9 +407,11 @@ MulticopterPositionControl::parameters_update(bool force)
param_get(_params_handles.z_vel_max, &v);
_params.vel_max(2) = v;
param_get(_params_handles.xy_ff, &v);
+ v = math::constrain(v, 0.0f, 1.0f);
_params.vel_ff(0) = v;
_params.vel_ff(1) = v;
param_get(_params_handles.z_ff, &v);
+ v = math::constrain(v, 0.0f, 1.0f);
_params.vel_ff(2) = v;
_params.sp_offs_max = _params.vel_max.edivide(_params.pos_p) * 2.0f;
@@ -497,8 +514,11 @@ MulticopterPositionControl::reset_pos_sp()
{
if (_reset_pos_sp) {
_reset_pos_sp = false;
- _pos_sp(0) = _pos(0);
- _pos_sp(1) = _pos(1);
+ /* shift position setpoint to make attitude setpoint continuous */
+ _pos_sp(0) = _pos(0) + (_vel(0) - _att_sp.R_body[0][2] * _att_sp.thrust / _params.vel_p(0)
+ - _params.vel_ff(0) * _sp_move_rate(0)) / _params.pos_p(0);
+ _pos_sp(1) = _pos(1) + (_vel(1) - _att_sp.R_body[1][2] * _att_sp.thrust / _params.vel_p(1)
+ - _params.vel_ff(1) * _sp_move_rate(1)) / _params.pos_p(1);
mavlink_log_info(_mavlink_fd, "[mpc] reset pos sp: %.2f, %.2f", (double)_pos_sp(0), (double)_pos_sp(1));
}
}
@@ -508,12 +528,126 @@ MulticopterPositionControl::reset_alt_sp()
{
if (_reset_alt_sp) {
_reset_alt_sp = false;
- _pos_sp(2) = _pos(2);
+ _pos_sp(2) = _pos(2) + (_vel(2) - _params.vel_ff(2) * _sp_move_rate(2)) / _params.pos_p(2);
mavlink_log_info(_mavlink_fd, "[mpc] reset alt sp: %.2f", -(double)_pos_sp(2));
}
}
void
+MulticopterPositionControl::control_manual(float dt)
+{
+ _sp_move_rate.zero();
+
+ if (_control_mode.flag_control_altitude_enabled) {
+ /* move altitude setpoint with throttle stick */
+ _sp_move_rate(2) = -scale_control(_manual.z - 0.5f, 0.5f, alt_ctl_dz);
+ }
+
+ if (_control_mode.flag_control_position_enabled) {
+ /* move position setpoint with roll/pitch stick */
+ _sp_move_rate(0) = _manual.x;
+ _sp_move_rate(1) = _manual.y;
+ }
+
+ /* limit setpoint move rate */
+ float sp_move_norm = _sp_move_rate.length();
+
+ if (sp_move_norm > 1.0f) {
+ _sp_move_rate /= sp_move_norm;
+ }
+
+ /* _sp_move_rate scaled to 0..1, scale it to max speed and rotate around yaw */
+ math::Matrix<3, 3> R_yaw_sp;
+ R_yaw_sp.from_euler(0.0f, 0.0f, _att_sp.yaw_body);
+ _sp_move_rate = R_yaw_sp * _sp_move_rate.emult(_params.vel_max);
+
+ if (_control_mode.flag_control_altitude_enabled) {
+ /* reset alt setpoint to current altitude if needed */
+ reset_alt_sp();
+ }
+
+ if (_control_mode.flag_control_position_enabled) {
+ /* reset position setpoint to current position if needed */
+ reset_pos_sp();
+ }
+
+ /* feed forward setpoint move rate with weight vel_ff */
+ _vel_ff = _sp_move_rate.emult(_params.vel_ff);
+
+ /* move position setpoint */
+ _pos_sp += _sp_move_rate * dt;
+
+ /* check if position setpoint is too far from actual position */
+ math::Vector<3> pos_sp_offs;
+ pos_sp_offs.zero();
+
+ if (_control_mode.flag_control_position_enabled) {
+ pos_sp_offs(0) = (_pos_sp(0) - _pos(0)) / _params.sp_offs_max(0);
+ pos_sp_offs(1) = (_pos_sp(1) - _pos(1)) / _params.sp_offs_max(1);
+ }
+
+ if (_control_mode.flag_control_altitude_enabled) {
+ pos_sp_offs(2) = (_pos_sp(2) - _pos(2)) / _params.sp_offs_max(2);
+ }
+
+ float pos_sp_offs_norm = pos_sp_offs.length();
+
+ if (pos_sp_offs_norm > 1.0f) {
+ pos_sp_offs /= pos_sp_offs_norm;
+ _pos_sp = _pos + pos_sp_offs.emult(_params.sp_offs_max);
+ }
+}
+
+void
+MulticopterPositionControl::control_offboard(float dt)
+{
+ bool updated;
+ orb_check(_pos_sp_triplet_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(position_setpoint_triplet), _pos_sp_triplet_sub, &_pos_sp_triplet);
+ }
+
+ if (_pos_sp_triplet.current.valid) {
+ if (_control_mode.flag_control_position_enabled && _pos_sp_triplet.current.position_valid) {
+ /* control position */
+ _pos_sp(0) = _pos_sp_triplet.current.x;
+ _pos_sp(1) = _pos_sp_triplet.current.y;
+ _pos_sp(2) = _pos_sp_triplet.current.z;
+ _att_sp.yaw_body = _pos_sp_triplet.current.yaw;
+
+ } else if (_control_mode.flag_control_velocity_enabled && _pos_sp_triplet.current.velocity_valid) {
+ /* control velocity */
+ /* reset position setpoint to current position if needed */
+ reset_pos_sp();
+
+ /* set position setpoint move rate */
+ _sp_move_rate(0) = _pos_sp_triplet.current.vx;
+ _sp_move_rate(1) = _pos_sp_triplet.current.vy;
+ _att_sp.yaw_body = _att_sp.yaw_body + _pos_sp_triplet.current.yawspeed * dt;
+ }
+
+ if (_control_mode.flag_control_altitude_enabled) {
+ /* reset alt setpoint to current altitude if needed */
+ reset_alt_sp();
+
+ /* set altitude setpoint move rate */
+ _sp_move_rate(2) = _pos_sp_triplet.current.vz;
+ }
+
+ /* feed forward setpoint move rate with weight vel_ff */
+ _vel_ff = _sp_move_rate.emult(_params.vel_ff);
+
+ /* move position setpoint */
+ _pos_sp += _sp_move_rate * dt;
+
+ } else {
+ reset_pos_sp();
+ reset_alt_sp();
+ }
+}
+
+void
MulticopterPositionControl::task_main()
{
warnx("started");
@@ -551,13 +685,6 @@ MulticopterPositionControl::task_main()
hrt_abstime t_prev = 0;
- const float alt_ctl_dz = 0.2f;
-
- math::Vector<3> sp_move_rate;
- sp_move_rate.zero();
-
- float yaw_sp_move_rate;
-
math::Vector<3> thrust_int;
thrust_int.zero();
math::Matrix<3, 3> R;
@@ -616,138 +743,17 @@ MulticopterPositionControl::task_main()
_vel(1) = _local_pos.vy;
_vel(2) = _local_pos.vz;
- sp_move_rate.zero();
+ _vel_ff.zero();
+ _sp_move_rate.zero();
/* select control source */
if (_control_mode.flag_control_manual_enabled) {
/* manual control */
- if (_control_mode.flag_control_altitude_enabled) {
- /* reset alt setpoint to current altitude if needed */
- reset_alt_sp();
-
- /* move altitude setpoint with throttle stick */
- sp_move_rate(2) = -scale_control(_manual.z - 0.5f, 0.5f, alt_ctl_dz);
- }
-
- if (_control_mode.flag_control_position_enabled) {
- /* reset position setpoint to current position if needed */
- reset_pos_sp();
-
- /* move position setpoint with roll/pitch stick */
- sp_move_rate(0) = _manual.x;
- sp_move_rate(1) = _manual.y;
- }
-
- /* limit setpoint move rate */
- float sp_move_norm = sp_move_rate.length();
-
- if (sp_move_norm > 1.0f) {
- sp_move_rate /= sp_move_norm;
- }
-
- /* scale to max speed and rotate around yaw */
- math::Matrix<3, 3> R_yaw_sp;
- R_yaw_sp.from_euler(0.0f, 0.0f, _att_sp.yaw_body);
- sp_move_rate = R_yaw_sp * sp_move_rate.emult(_params.vel_max);
-
- /* move position setpoint */
- _pos_sp += sp_move_rate * dt;
-
- /* check if position setpoint is too far from actual position */
- math::Vector<3> pos_sp_offs;
- pos_sp_offs.zero();
-
- if (_control_mode.flag_control_position_enabled) {
- pos_sp_offs(0) = (_pos_sp(0) - _pos(0)) / _params.sp_offs_max(0);
- pos_sp_offs(1) = (_pos_sp(1) - _pos(1)) / _params.sp_offs_max(1);
- }
-
- if (_control_mode.flag_control_altitude_enabled) {
- pos_sp_offs(2) = (_pos_sp(2) - _pos(2)) / _params.sp_offs_max(2);
- }
-
- float pos_sp_offs_norm = pos_sp_offs.length();
-
- if (pos_sp_offs_norm > 1.0f) {
- pos_sp_offs /= pos_sp_offs_norm;
- _pos_sp = _pos + pos_sp_offs.emult(_params.sp_offs_max);
- }
+ control_manual(dt);
} else if (_control_mode.flag_control_offboard_enabled) {
- /* Offboard control */
- bool updated;
- orb_check(_pos_sp_triplet_sub, &updated);
-
- if (updated) {
- orb_copy(ORB_ID(position_setpoint_triplet), _pos_sp_triplet_sub, &_pos_sp_triplet);
- }
-
- if (_pos_sp_triplet.current.valid) {
-
- if (_control_mode.flag_control_position_enabled && _pos_sp_triplet.current.position_valid) {
-
- _pos_sp(0) = _pos_sp_triplet.current.x;
- _pos_sp(1) = _pos_sp_triplet.current.y;
- _pos_sp(2) = _pos_sp_triplet.current.z;
- _att_sp.yaw_body = _pos_sp_triplet.current.yaw;
-
- } else if (_control_mode.flag_control_velocity_enabled && _pos_sp_triplet.current.velocity_valid) {
- /* reset position setpoint to current position if needed */
- reset_pos_sp();
- /* move position setpoint with roll/pitch stick */
- sp_move_rate(0) = _pos_sp_triplet.current.vx;
- sp_move_rate(1) = _pos_sp_triplet.current.vy;
- yaw_sp_move_rate = _pos_sp_triplet.current.yawspeed;
- _att_sp.yaw_body = _att.yaw + yaw_sp_move_rate * dt;
- }
-
- if (_control_mode.flag_control_altitude_enabled) {
- /* reset alt setpoint to current altitude if needed */
- reset_alt_sp();
-
- /* move altitude setpoint with throttle stick */
- sp_move_rate(2) = -scale_control(_pos_sp_triplet.current.vz - 0.5f, 0.5f, alt_ctl_dz);;
- }
-
- /* limit setpoint move rate */
- float sp_move_norm = sp_move_rate.length();
-
- if (sp_move_norm > 1.0f) {
- sp_move_rate /= sp_move_norm;
- }
-
- /* scale to max speed and rotate around yaw */
- math::Matrix<3, 3> R_yaw_sp;
- R_yaw_sp.from_euler(0.0f, 0.0f, _att_sp.yaw_body);
- sp_move_rate = R_yaw_sp * sp_move_rate.emult(_params.vel_max);
-
- /* move position setpoint */
- _pos_sp += sp_move_rate * dt;
-
- /* check if position setpoint is too far from actual position */
- math::Vector<3> pos_sp_offs;
- pos_sp_offs.zero();
-
- if (_control_mode.flag_control_position_enabled) {
- pos_sp_offs(0) = (_pos_sp(0) - _pos(0)) / _params.sp_offs_max(0);
- pos_sp_offs(1) = (_pos_sp(1) - _pos(1)) / _params.sp_offs_max(1);
- }
-
- if (_control_mode.flag_control_altitude_enabled) {
- pos_sp_offs(2) = (_pos_sp(2) - _pos(2)) / _params.sp_offs_max(2);
- }
-
- float pos_sp_offs_norm = pos_sp_offs.length();
-
- if (pos_sp_offs_norm > 1.0f) {
- pos_sp_offs /= pos_sp_offs_norm;
- _pos_sp = _pos + pos_sp_offs.emult(_params.sp_offs_max);
- }
-
- } else {
- reset_pos_sp();
- reset_alt_sp();
- }
+ /* offboard control */
+ control_offboard(dt);
} else {
/* AUTO */
@@ -782,6 +788,7 @@ MulticopterPositionControl::task_main()
}
/* fill local position setpoint */
+ _local_pos_sp.timestamp = hrt_absolute_time();
_local_pos_sp.x = _pos_sp(0);
_local_pos_sp.y = _pos_sp(1);
_local_pos_sp.z = _pos_sp(2);
@@ -821,7 +828,7 @@ MulticopterPositionControl::task_main()
/* run position & altitude controllers, calculate velocity setpoint */
math::Vector<3> pos_err = _pos_sp - _pos;
- _vel_sp = pos_err.emult(_params.pos_p) + sp_move_rate.emult(_params.vel_ff);
+ _vel_sp = pos_err.emult(_params.pos_p) + _vel_ff;
if (!_control_mode.flag_control_altitude_enabled) {
_reset_alt_sp = true;
@@ -901,7 +908,7 @@ MulticopterPositionControl::task_main()
math::Vector<3> vel_err = _vel_sp - _vel;
/* derivative of velocity error, not includes setpoint acceleration */
- math::Vector<3> vel_err_d = (sp_move_rate - _vel).emult(_params.pos_p) - (_vel - _vel_prev) / dt;
+ math::Vector<3> vel_err_d = (_sp_move_rate - _vel).emult(_params.pos_p) - (_vel - _vel_prev) / dt;
_vel_prev = _vel;
/* thrust vector in NED frame */
diff --git a/src/modules/uORB/topics/position_setpoint_triplet.h b/src/modules/uORB/topics/position_setpoint_triplet.h
index 4a1932180..ec2131abd 100644
--- a/src/modules/uORB/topics/position_setpoint_triplet.h
+++ b/src/modules/uORB/topics/position_setpoint_triplet.h
@@ -60,7 +60,7 @@ enum SETPOINT_TYPE
SETPOINT_TYPE_TAKEOFF, /**< takeoff setpoint */
SETPOINT_TYPE_LAND, /**< land setpoint, altitude must be ignored, descend until landing */
SETPOINT_TYPE_IDLE, /**< do nothing, switch off motors or keep at idle speed (MC) */
- SETPOINT_TYPE_OFFBOARD, /**< setpoint set by offboard */
+ SETPOINT_TYPE_OFFBOARD, /**< setpoint in NED frame (x, y, z, vx, vy, vz) set by offboard */
};
struct position_setpoint_s
@@ -71,9 +71,9 @@ struct position_setpoint_s
float y; /**< local position setpoint in m in NED */
float z; /**< local position setpoint in m in NED */
bool position_valid; /**< true if local position setpoint valid */
- float vx; /**< local velocity setpoint in m in NED */
- float vy; /**< local velocity setpoint in m in NED */
- float vz; /**< local velocity setpoint in m in NED */
+ float vx; /**< local velocity setpoint in m/s in NED */
+ float vy; /**< local velocity setpoint in m/s in NED */
+ float vz; /**< local velocity setpoint in m/s in NED */
bool velocity_valid; /**< true if local velocity setpoint valid */
double lat; /**< latitude, in deg */
double lon; /**< longitude, in deg */
diff --git a/src/modules/uORB/topics/vehicle_local_position_setpoint.h b/src/modules/uORB/topics/vehicle_local_position_setpoint.h
index 8988a0330..6766bb58a 100644
--- a/src/modules/uORB/topics/vehicle_local_position_setpoint.h
+++ b/src/modules/uORB/topics/vehicle_local_position_setpoint.h
@@ -50,11 +50,12 @@
*/
struct vehicle_local_position_setpoint_s {
+ uint64_t timestamp; /**< timestamp of the setpoint */
float x; /**< in meters NED */
float y; /**< in meters NED */
float z; /**< in meters NED */
float yaw; /**< in radians NED -PI..+PI */
-}; /**< Local position in NED frame to go to */
+}; /**< Local position in NED frame */
/**
* @}