forked from Archive/PX4-Autopilot
FlightTasks: switch field name from thr to thrust + some code spacing
This commit is contained in:
parent
f8e4e82bba
commit
f135e6dda0
|
@ -1,15 +1,15 @@
|
|||
# Local position setpoint in NED frame
|
||||
# setting something to NaN means the state should not be controlled
|
||||
|
||||
float32 x # in meters NED
|
||||
float32 y # in meters NED
|
||||
float32 z # in meters NED
|
||||
float32 yaw # in radians NED -PI..+PI
|
||||
float32 yawspeed# in radians/sec
|
||||
float32 vx # in meters/sec
|
||||
float32 vy # in meters/sec
|
||||
float32 vz # in meters/sec
|
||||
float32 acc_x # in meters/(sec*sec)
|
||||
float32 acc_y # in meters/(sec*sec)
|
||||
float32 acc_z # in meters/(sec*sec)
|
||||
float32[3] thr # normalized thrust vector in NED
|
||||
float32 x # in meters NED
|
||||
float32 y # in meters NED
|
||||
float32 z # in meters NED
|
||||
float32 yaw # in radians NED -PI..+PI
|
||||
float32 yawspeed # in radians/sec
|
||||
float32 vx # in meters/sec
|
||||
float32 vy # in meters/sec
|
||||
float32 vz # in meters/sec
|
||||
float32 acc_x # in meters/(sec*sec)
|
||||
float32 acc_y # in meters/(sec*sec)
|
||||
float32 acc_z # in meters/(sec*sec)
|
||||
float32[3] thrust # normalized thrust vector in NED
|
||||
|
|
|
@ -131,7 +131,7 @@ protected:
|
|||
void _setYawspeedSetpoint(const float &yawspeed) { _vehicle_local_position_setpoint.yawspeed = yawspeed; }
|
||||
|
||||
/* Put the thrust setpoint produced by the task into the setpoint message */
|
||||
void _setThrustSetpoint(const matrix::Vector3f &thrust_setpoint) { thrust_setpoint.copyTo(_vehicle_local_position_setpoint.thr);}
|
||||
void _setThrustSetpoint(const matrix::Vector3f &thrust_setpoint) { thrust_setpoint.copyTo(_vehicle_local_position_setpoint.thrust); }
|
||||
|
||||
private:
|
||||
uORB::Subscription<vehicle_local_position_s> *_sub_vehicle_local_position{nullptr};
|
||||
|
|
|
@ -90,7 +90,7 @@ void PositionControl::updateSetpoint(struct vehicle_local_position_setpoint_s se
|
|||
_pos_sp = Data(&setpoint.x);
|
||||
_vel_sp = Data(&setpoint.vx);
|
||||
_acc_sp = Data(&setpoint.acc_x);
|
||||
_thr_sp = Data(setpoint.thr);
|
||||
_thr_sp = Data(setpoint.thrust);
|
||||
_yaw_sp = setpoint.yaw; //integrate
|
||||
_yawspeed_sp = setpoint.yawspeed;
|
||||
_interfaceMapping();
|
||||
|
@ -100,7 +100,7 @@ void PositionControl::updateSetpoint(struct vehicle_local_position_setpoint_s se
|
|||
*/
|
||||
_skipController = false;
|
||||
|
||||
if (PX4_ISFINITE(setpoint.thr[0]) && PX4_ISFINITE(setpoint.thr[1]) && PX4_ISFINITE(setpoint.thr[2])) {
|
||||
if (PX4_ISFINITE(setpoint.thrust[0]) && PX4_ISFINITE(setpoint.thrust[1]) && PX4_ISFINITE(setpoint.thrust[2])) {
|
||||
_skipController = true;
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue