forked from Archive/PX4-Autopilot
Distinction between yaw position and yaw speed control, just messsed around in the code, untested
This commit is contained in:
parent
9c8e031f6b
commit
2652b16d37
|
@ -105,6 +105,7 @@ mc_thread_main(int argc, char *argv[])
|
||||||
memset(&rates_sp, 0, sizeof(rates_sp));
|
memset(&rates_sp, 0, sizeof(rates_sp));
|
||||||
|
|
||||||
struct actuator_controls_s actuators;
|
struct actuator_controls_s actuators;
|
||||||
|
memset(&actuators, 0, sizeof(actuators));
|
||||||
|
|
||||||
/* subscribe to attitude, motor setpoints and system state */
|
/* subscribe to attitude, motor setpoints and system state */
|
||||||
int att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
|
int att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
|
||||||
|
@ -151,10 +152,14 @@ mc_thread_main(int argc, char *argv[])
|
||||||
bool flag_control_attitude_enabled = false;
|
bool flag_control_attitude_enabled = false;
|
||||||
bool flag_system_armed = false;
|
bool flag_system_armed = false;
|
||||||
|
|
||||||
|
/* store if yaw position or yaw speed has been changed */
|
||||||
|
bool control_yaw_position = true;
|
||||||
|
|
||||||
/* prepare the handle for the failsafe throttle */
|
/* prepare the handle for the failsafe throttle */
|
||||||
param_t failsafe_throttle_handle = param_find("MC_RCLOSS_THR");
|
param_t failsafe_throttle_handle = param_find("MC_RCLOSS_THR");
|
||||||
float failsafe_throttle = 0.0f;
|
float failsafe_throttle = 0.0f;
|
||||||
|
|
||||||
|
|
||||||
while (!thread_should_exit) {
|
while (!thread_should_exit) {
|
||||||
|
|
||||||
/* wait for a sensor update, check for exit condition every 500 ms */
|
/* wait for a sensor update, check for exit condition every 500 ms */
|
||||||
|
@ -205,28 +210,27 @@ mc_thread_main(int argc, char *argv[])
|
||||||
|
|
||||||
/** STEP 1: Define which input is the dominating control input */
|
/** STEP 1: Define which input is the dominating control input */
|
||||||
if (state.flag_control_offboard_enabled) {
|
if (state.flag_control_offboard_enabled) {
|
||||||
/* offboard inputs */
|
/* offboard inputs */
|
||||||
if (offboard_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_RATES) {
|
if (offboard_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_RATES) {
|
||||||
rates_sp.roll = offboard_sp.p1;
|
rates_sp.roll = offboard_sp.p1;
|
||||||
rates_sp.pitch = offboard_sp.p2;
|
rates_sp.pitch = offboard_sp.p2;
|
||||||
rates_sp.yaw = offboard_sp.p3;
|
rates_sp.yaw = offboard_sp.p3;
|
||||||
rates_sp.thrust = offboard_sp.p4;
|
rates_sp.thrust = offboard_sp.p4;
|
||||||
// printf("thrust_rate=%8.4f\n",offboard_sp.p4);
|
// printf("thrust_rate=%8.4f\n",offboard_sp.p4);
|
||||||
rates_sp.timestamp = hrt_absolute_time();
|
rates_sp.timestamp = hrt_absolute_time();
|
||||||
orb_publish(ORB_ID(vehicle_rates_setpoint), rates_sp_pub, &rates_sp);
|
orb_publish(ORB_ID(vehicle_rates_setpoint), rates_sp_pub, &rates_sp);
|
||||||
} else if (offboard_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE) {
|
} else if (offboard_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE) {
|
||||||
att_sp.roll_body = offboard_sp.p1;
|
att_sp.roll_body = offboard_sp.p1;
|
||||||
att_sp.pitch_body = offboard_sp.p2;
|
att_sp.pitch_body = offboard_sp.p2;
|
||||||
att_sp.yaw_body = offboard_sp.p3;
|
att_sp.yaw_body = offboard_sp.p3;
|
||||||
att_sp.thrust = offboard_sp.p4;
|
att_sp.thrust = offboard_sp.p4;
|
||||||
// printf("thrust_att=%8.4f\n",offboard_sp.p4);
|
// printf("thrust_att=%8.4f\n",offboard_sp.p4);
|
||||||
att_sp.timestamp = hrt_absolute_time();
|
att_sp.timestamp = hrt_absolute_time();
|
||||||
/* STEP 2: publish the result to the vehicle actuators */
|
/* STEP 2: publish the result to the vehicle actuators */
|
||||||
orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
|
orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
|
||||||
}
|
}
|
||||||
|
/* decide wether we want rate or position input */
|
||||||
/* decide wether we want rate or position input */
|
}
|
||||||
}
|
|
||||||
else if (state.flag_control_manual_enabled) {
|
else if (state.flag_control_manual_enabled) {
|
||||||
|
|
||||||
/* manual inputs, from RC control or joystick */
|
/* manual inputs, from RC control or joystick */
|
||||||
|
@ -277,14 +281,29 @@ mc_thread_main(int argc, char *argv[])
|
||||||
att_sp.pitch_body = manual.pitch;
|
att_sp.pitch_body = manual.pitch;
|
||||||
|
|
||||||
/* only move setpoint if manual input is != 0 */
|
/* only move setpoint if manual input is != 0 */
|
||||||
// XXX turn into param
|
|
||||||
if ((manual.yaw < -0.01f || 0.01f < manual.yaw) && manual.throttle > 0.3f) {
|
if(manual.mode == MANUAL_CONTROL_MODE_ATT_YAW_POS) {
|
||||||
att_sp.yaw_body = att_sp.yaw_body + manual.yaw * 0.0025f;
|
// XXX turn into param
|
||||||
} else if (manual.throttle <= 0.3f) {
|
if ((manual.yaw < -0.01f || 0.01f < manual.yaw) && manual.throttle > 0.3f) {
|
||||||
att_sp.yaw_body = att.yaw;
|
att_sp.yaw_body = att_sp.yaw_body + manual.yaw * 0.0025f;
|
||||||
|
} else if (manual.throttle <= 0.3f) {
|
||||||
|
att_sp.yaw_body = att.yaw;
|
||||||
|
}
|
||||||
|
control_yaw_position = true;
|
||||||
|
} else if (manual.mode == MANUAL_CONTROL_MODE_ATT_YAW_RATE) {
|
||||||
|
if ((manual.yaw < -0.01f || 0.01f < manual.yaw) && manual.throttle > 0.3f) {
|
||||||
|
rates_sp.yaw = manual.yaw;
|
||||||
|
control_yaw_position = false;
|
||||||
|
} else {
|
||||||
|
att_sp.yaw_body = 0.0f;
|
||||||
|
control_yaw_position = true;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
att_sp.thrust = manual.throttle;
|
att_sp.thrust = manual.throttle;
|
||||||
att_sp.timestamp = hrt_absolute_time();
|
att_sp.timestamp = hrt_absolute_time();
|
||||||
|
|
||||||
|
//rates_sp.yaw = manual.yaw;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
/* STEP 2: publish the result to the vehicle actuators */
|
/* STEP 2: publish the result to the vehicle actuators */
|
||||||
|
@ -305,7 +324,10 @@ mc_thread_main(int argc, char *argv[])
|
||||||
|
|
||||||
/** STEP 3: Identify the controller setup to run and set up the inputs correctly */
|
/** STEP 3: Identify the controller setup to run and set up the inputs correctly */
|
||||||
if (state.flag_control_attitude_enabled) {
|
if (state.flag_control_attitude_enabled) {
|
||||||
multirotor_control_attitude(&att_sp, &att, &rates_sp, NULL);
|
multirotor_control_attitude(&att_sp, &att, &rates_sp, NULL, control_yaw_position);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
orb_publish(ORB_ID(vehicle_rates_setpoint), rates_sp_pub, &rates_sp);
|
orb_publish(ORB_ID(vehicle_rates_setpoint), rates_sp_pub, &rates_sp);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -158,7 +158,7 @@ static int parameters_update(const struct mc_att_control_param_handles *h, struc
|
||||||
}
|
}
|
||||||
|
|
||||||
void multirotor_control_attitude(const struct vehicle_attitude_setpoint_s *att_sp,
|
void multirotor_control_attitude(const struct vehicle_attitude_setpoint_s *att_sp,
|
||||||
const struct vehicle_attitude_s *att, struct vehicle_rates_setpoint_s *rates_sp, struct actuator_controls_s *actuators)
|
const struct vehicle_attitude_s *att, struct vehicle_rates_setpoint_s *rates_sp, struct actuator_controls_s *actuators, bool control_yaw_position)
|
||||||
{
|
{
|
||||||
static uint64_t last_run = 0;
|
static uint64_t last_run = 0;
|
||||||
static uint64_t last_input = 0;
|
static uint64_t last_input = 0;
|
||||||
|
@ -216,9 +216,10 @@ void multirotor_control_attitude(const struct vehicle_attitude_setpoint_s *att_s
|
||||||
rates_sp->roll = pid_calculate(&roll_controller, att_sp->roll_body ,
|
rates_sp->roll = pid_calculate(&roll_controller, att_sp->roll_body ,
|
||||||
att->roll, att->rollspeed, deltaT);
|
att->roll, att->rollspeed, deltaT);
|
||||||
|
|
||||||
/* control yaw rate */
|
if(control_yaw_position) {
|
||||||
rates_sp->yaw = p.yaw_p * atan2f(cosf(att->yaw - att_sp->yaw_body), sinf(att->yaw - att_sp->yaw_body)) - (p.yaw_d * att->yawspeed);
|
/* control yaw rate */
|
||||||
|
rates_sp->yaw = p.yaw_p * atan2f(cosf(att->yaw - att_sp->yaw_body), sinf(att->yaw - att_sp->yaw_body)) - (p.yaw_d * att->yawspeed);
|
||||||
|
}
|
||||||
rates_sp->thrust = att_sp->thrust;
|
rates_sp->thrust = att_sp->thrust;
|
||||||
|
|
||||||
motor_skip_counter++;
|
motor_skip_counter++;
|
||||||
|
|
|
@ -52,6 +52,6 @@
|
||||||
#include <uORB/topics/actuator_controls.h>
|
#include <uORB/topics/actuator_controls.h>
|
||||||
|
|
||||||
void multirotor_control_attitude(const struct vehicle_attitude_setpoint_s *att_sp,
|
void multirotor_control_attitude(const struct vehicle_attitude_setpoint_s *att_sp,
|
||||||
const struct vehicle_attitude_s *att, struct vehicle_rates_setpoint_s *rates_sp, struct actuator_controls_s *actuators);
|
const struct vehicle_attitude_s *att, struct vehicle_rates_setpoint_s *rates_sp, struct actuator_controls_s *, bool control_yaw_position);
|
||||||
|
|
||||||
#endif /* MULTIROTOR_ATTITUDE_CONTROL_H_ */
|
#endif /* MULTIROTOR_ATTITUDE_CONTROL_H_ */
|
||||||
|
|
|
@ -48,13 +48,6 @@
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/**
|
|
||||||
* Defines how RC channels map to control inputs.
|
|
||||||
*
|
|
||||||
* The default mode on quadrotors and fixed wing is
|
|
||||||
* roll and pitch position of the right stick and
|
|
||||||
* throttle and yaw rate on the left stick
|
|
||||||
*/
|
|
||||||
enum MANUAL_CONTROL_MODE
|
enum MANUAL_CONTROL_MODE
|
||||||
{
|
{
|
||||||
MANUAL_CONTROL_MODE_DIRECT = 0,
|
MANUAL_CONTROL_MODE_DIRECT = 0,
|
||||||
|
|
Loading…
Reference in New Issue