aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mc_pos_control
diff options
context:
space:
mode:
authort0ni0 <azntonio789@gmail.com>2014-06-08 15:21:02 -0400
committert0ni0 <azntonio789@gmail.com>2014-06-08 15:22:04 -0400
commit0a86fd0d9f3f3ba1a007ff54e1d498e7735d4aa5 (patch)
treea70b22465705c4b5d00f46d95ad2d9370e5263d0 /src/modules/mc_pos_control
parent2a79a9a4e4ebae2e85dab64ae98ff2a17e421ea2 (diff)
downloadpx4-firmware-0a86fd0d9f3f3ba1a007ff54e1d498e7735d4aa5.tar.gz
px4-firmware-0a86fd0d9f3f3ba1a007ff54e1d498e7735d4aa5.tar.bz2
px4-firmware-0a86fd0d9f3f3ba1a007ff54e1d498e7735d4aa5.zip
Changed struct name used for local_pos_sp
Diffstat (limited to 'src/modules/mc_pos_control')
-rw-r--r--src/modules/mc_pos_control/mc_pos_control_main.cpp21
1 files changed, 9 insertions, 12 deletions
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 4ee78516f..6a105762b 100644
--- a/src/modules/mc_pos_control/mc_pos_control_main.cpp
+++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp
@@ -118,7 +118,7 @@ private:
int _arming_sub; /**< arming status of outputs */
int _local_pos_sub; /**< vehicle local position */
int _pos_sp_triplet_sub; /**< position setpoint triplet */
- int _offboard_control_pos_sp_sub; /**< offboard control position setpoint */
+ int _local_pos_sp_sub; /**< offboard local position setpoint */
orb_advert_t _att_sp_pub; /**< attitude setpoint publication */
orb_advert_t _local_pos_sp_pub; /**< vehicle local position setpoint publication */
@@ -133,7 +133,6 @@ private:
struct position_setpoint_triplet_s _pos_sp_triplet; /**< vehicle global position setpoint triplet */
struct vehicle_local_position_setpoint_s _local_pos_sp; /**< vehicle local position setpoint */
struct vehicle_global_velocity_setpoint_s _global_vel_sp; /**< vehicle global velocity setpoint */
- struct vehicle_local_position_setpoint_s _offboard_control_pos_sp; /**< offboard control position setpoint */
struct {
@@ -280,7 +279,6 @@ MulticopterPositionControl::MulticopterPositionControl() :
memset(&_pos_sp_triplet, 0, sizeof(_pos_sp_triplet));
memset(&_local_pos_sp, 0, sizeof(_local_pos_sp));
memset(&_global_vel_sp, 0, sizeof(_global_vel_sp));
- memset(&_offboard_control_pos_sp, 0, sizeof(_offboard_control_pos_sp));
memset(&_ref_pos, 0, sizeof(_ref_pos));
@@ -532,7 +530,7 @@ MulticopterPositionControl::task_main()
_arming_sub = orb_subscribe(ORB_ID(actuator_armed));
_local_pos_sub = orb_subscribe(ORB_ID(vehicle_local_position));
_pos_sp_triplet_sub = orb_subscribe(ORB_ID(position_setpoint_triplet));
- _offboard_control_pos_sp_sub = orb_subscribe(ORB_ID(vehicle_local_position_setpoint));
+ _local_pos_sp_sub = orb_subscribe(ORB_ID(vehicle_local_position_setpoint));
parameters_update(true);
@@ -671,26 +669,25 @@ MulticopterPositionControl::task_main()
} else if (_control_mode.flag_control_offboard_enabled) {
/* Offboard control */
- /* Team elikos doesn't really know what it is doing */
bool updated;
- orb_check(_offboard_control_pos_sp_sub, &updated);
+ orb_check(_local_pos_sp_sub, &updated);
if (updated) {
- orb_copy(ORB_ID(vehicle_local_position_setpoint), _offboard_control_pos_sp_sub,
- &_offboard_control_pos_sp);
+ orb_copy(ORB_ID(vehicle_local_position_setpoint), _local_pos_sp_sub,
+ &_local_pos_sp);
}
/* Make sure position control is selected i.e. not only velocity control */
if (_control_mode.flag_control_position_enabled) {
- _pos_sp(0) = _offboard_control_pos_sp.x;
- _pos_sp(1) = _offboard_control_pos_sp.y;
+ _pos_sp(0) = _local_pos_sp.x;
+ _pos_sp(1) = _local_pos_sp.y;
}
if (_control_mode.flag_control_altitude_enabled) {
- _pos_sp(2) = _offboard_control_pos_sp.z;
+ _pos_sp(2) = _local_pos_sp.z;
}
- _att_sp.yaw_body = _offboard_control_pos_sp.yaw;
+ _att_sp.yaw_body = _local_pos_sp.yaw;
} else {
/* AUTO */