From 90873474a9c52b66696f31c12b35b25ab0f6abd6 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Tue, 10 Sep 2013 22:58:44 +0200 Subject: multirotor_pos_control: setpint reset rewritten --- .../multirotor_pos_control.c | 117 ++++++++++++--------- src/modules/systemlib/pid/pid.c | 28 +++-- 2 files changed, 86 insertions(+), 59 deletions(-) (limited to 'src/modules') diff --git a/src/modules/multirotor_pos_control/multirotor_pos_control.c b/src/modules/multirotor_pos_control/multirotor_pos_control.c index 336523072..1b3ddfdcd 100644 --- a/src/modules/multirotor_pos_control/multirotor_pos_control.c +++ b/src/modules/multirotor_pos_control/multirotor_pos_control.c @@ -212,17 +212,17 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[]) orb_advert_t global_vel_sp_pub = orb_advertise(ORB_ID(vehicle_global_velocity_setpoint), &global_vel_sp); orb_advert_t att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &att_sp); - bool global_pos_sp_reproject = false; + bool reset_mission_sp = false; bool global_pos_sp_valid = false; - bool local_pos_sp_valid = false; - bool reset_sp_z = true; - bool reset_sp_xy = true; + bool reset_man_sp_z = true; + bool reset_man_sp_xy = true; bool reset_int_z = true; bool reset_int_z_manual = false; bool reset_int_xy = true; bool was_armed = false; - bool reset_integral = true; - bool reset_auto_pos = true; + bool reset_auto_sp_xy = true; + bool reset_auto_sp_z = true; + bool reset_takeoff_sp = true; hrt_abstime t_prev = 0; const float alt_ctl_dz = 0.2f; @@ -270,11 +270,11 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[]) /* use integral_limit_out = tilt_max / 2 */ float i_limit; - if (params.xy_vel_i == 0.0f) { + if (params.xy_vel_i > 0.0f) { i_limit = params.tilt_max / params.xy_vel_i / 2.0f; } else { - i_limit = 1.0f; // not used really + i_limit = 0.0f; // not used } pid_set_parameters(&(xy_vel_pids[i]), params.xy_vel_p, params.xy_vel_i, params.xy_vel_d, i_limit, params.tilt_max); @@ -297,7 +297,7 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[]) if (updated) { orb_copy(ORB_ID(vehicle_global_position_setpoint), global_pos_sp_sub, &global_pos_sp); global_pos_sp_valid = true; - global_pos_sp_reproject = true; + reset_mission_sp = true; } hrt_abstime t = hrt_absolute_time(); @@ -312,8 +312,11 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[]) if (control_mode.flag_armed && !was_armed) { /* reset setpoints and integrals on arming */ - reset_sp_z = true; - reset_sp_xy = true; + reset_man_sp_z = true; + reset_man_sp_xy = true; + reset_auto_sp_z = true; + reset_auto_sp_xy = true; + reset_takeoff_sp = true; reset_int_z = true; reset_int_xy = true; } @@ -348,8 +351,8 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[]) /* reset setpoints to current position if needed */ if (control_mode.flag_control_altitude_enabled) { - if (reset_sp_z) { - reset_sp_z = false; + if (reset_man_sp_z) { + reset_man_sp_z = false; local_pos_sp.z = local_pos.z; mavlink_log_info(mavlink_fd, "[mpc] reset alt sp: %.2f", (double) - local_pos_sp.z); } @@ -371,8 +374,8 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[]) } if (control_mode.flag_control_position_enabled) { - if (reset_sp_xy) { - reset_sp_xy = false; + if (reset_man_sp_xy) { + reset_man_sp_xy = false; local_pos_sp.x = local_pos.x; local_pos_sp.y = local_pos.y; pid_reset_integral(&xy_vel_pids[0]); @@ -407,39 +410,43 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[]) local_pos_sp.yaw = att_sp.yaw_body; - /* local position setpoint is valid and can be used for loiter after position controlled mode */ - local_pos_sp_valid = control_mode.flag_control_position_enabled; - - reset_auto_pos = true; + /* local position setpoint is valid and can be used for auto loiter after position controlled mode */ + reset_auto_sp_xy = !control_mode.flag_control_position_enabled; + reset_auto_sp_z = !control_mode.flag_control_altitude_enabled; + reset_takeoff_sp = true; /* force reprojection of global setpoint after manual mode */ - global_pos_sp_reproject = true; + reset_mission_sp = true; } else if (control_mode.flag_control_auto_enabled) { /* AUTO mode, use global setpoint */ if (control_mode.auto_state == NAVIGATION_STATE_AUTO_READY) { - reset_auto_pos = true; + reset_auto_sp_xy = true; + reset_auto_sp_z = true; } else if (control_mode.auto_state == NAVIGATION_STATE_AUTO_TAKEOFF) { - if (reset_auto_pos) { + if (reset_takeoff_sp) { + reset_takeoff_sp = false; local_pos_sp.x = local_pos.x; local_pos_sp.y = local_pos.y; local_pos_sp.z = - params.takeoff_alt - params.takeoff_gap; local_pos_sp.yaw = att.yaw; - local_pos_sp_valid = true; att_sp.yaw_body = att.yaw; - reset_auto_pos = false; mavlink_log_info(mavlink_fd, "[mpc] takeoff sp: %.2f %.2f %.2f", (double)local_pos_sp.x, (double)local_pos_sp.y, (double) - local_pos_sp.z); } + reset_auto_sp_xy = false; + reset_auto_sp_z = true; + } else if (control_mode.auto_state == NAVIGATION_STATE_AUTO_RTL) { // TODO - reset_auto_pos = true; + reset_auto_sp_xy = true; + reset_auto_sp_z = true; } else if (control_mode.auto_state == NAVIGATION_STATE_AUTO_MISSION) { /* init local projection using local position ref */ if (local_pos.ref_timestamp != local_ref_timestamp) { - global_pos_sp_reproject = true; + reset_mission_sp = true; local_ref_timestamp = local_pos.ref_timestamp; double lat_home = local_pos.ref_lat * 1e-7; double lon_home = local_pos.ref_lon * 1e-7; @@ -447,9 +454,9 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[]) mavlink_log_info(mavlink_fd, "[mpc] local pos ref: %.7f, %.7f", (double)lat_home, (double)lon_home); } - if (global_pos_sp_reproject) { + if (reset_mission_sp) { + reset_mission_sp = false; /* update global setpoint projection */ - global_pos_sp_reproject = false; if (global_pos_sp_valid) { /* global position setpoint valid, use it */ @@ -471,33 +478,43 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[]) mavlink_log_info(mavlink_fd, "[mpc] new sp: %.7f, %.7f (%.2f, %.2f)", (double)sp_lat, sp_lon, (double)local_pos_sp.x, (double)local_pos_sp.y); } else { - if (!local_pos_sp_valid) { + if (reset_auto_sp_xy) { + reset_auto_sp_xy = false; /* local position setpoint is invalid, * use current position as setpoint for loiter */ local_pos_sp.x = local_pos.x; local_pos_sp.y = local_pos.y; - local_pos_sp.z = local_pos.z; local_pos_sp.yaw = att.yaw; - local_pos_sp_valid = true; + att_sp.yaw_body = global_pos_sp.yaw; + } + + if (reset_auto_sp_z) { + reset_auto_sp_z = false; + local_pos_sp.z = local_pos.z; } mavlink_log_info(mavlink_fd, "[mpc] no global pos sp, loiter: %.2f, %.2f", (double)local_pos_sp.x, (double)local_pos_sp.y); } } - reset_auto_pos = true; + reset_auto_sp_xy = true; + reset_auto_sp_z = true; + } + + if (control_mode.auto_state != NAVIGATION_STATE_AUTO_TAKEOFF) { + reset_takeoff_sp = true; } if (control_mode.auto_state != NAVIGATION_STATE_AUTO_MISSION) { - global_pos_sp_reproject = true; + reset_mission_sp = true; } /* reset setpoints after AUTO mode */ - reset_sp_xy = true; - reset_sp_z = true; + reset_man_sp_xy = true; + reset_man_sp_z = true; } else { - /* no control, loiter or stay on ground */ + /* no control (failsafe), loiter or stay on ground */ if (local_pos.landed) { /* landed: move setpoint down */ /* in air: hold altitude */ @@ -508,27 +525,30 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[]) mavlink_log_info(mavlink_fd, "[mpc] landed, set alt: %.2f", (double) - local_pos_sp.z); } - reset_sp_z = true; + reset_man_sp_z = true; } else { /* in air: hold altitude */ - if (reset_sp_z) { - reset_sp_z = false; + if (reset_man_sp_z) { + reset_man_sp_z = false; local_pos_sp.z = local_pos.z; mavlink_log_info(mavlink_fd, "[mpc] set loiter alt: %.2f", (double) - local_pos_sp.z); } + + reset_auto_sp_z = false; } if (control_mode.flag_control_position_enabled) { - if (reset_sp_xy) { - reset_sp_xy = false; + if (reset_man_sp_xy) { + reset_man_sp_xy = false; local_pos_sp.x = local_pos.x; local_pos_sp.y = local_pos.y; local_pos_sp.yaw = att.yaw; - local_pos_sp_valid = true; att_sp.yaw_body = att.yaw; mavlink_log_info(mavlink_fd, "[mpc] set loiter pos: %.2f %.2f", (double)local_pos_sp.x, (double)local_pos_sp.y); } + + reset_auto_sp_xy = false; } } @@ -540,7 +560,7 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[]) global_vel_sp.vz = pid_calculate(&z_pos_pid, local_pos_sp.z, local_pos.z, local_pos.vz - sp_move_rate[2], dt) + sp_move_rate[2]; } else { - reset_sp_z = true; + reset_man_sp_z = true; global_vel_sp.vz = 0.0f; } @@ -558,7 +578,7 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[]) } } else { - reset_sp_xy = true; + reset_man_sp_xy = true; global_vel_sp.vx = 0.0f; global_vel_sp.vy = 0.0f; } @@ -640,12 +660,13 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[]) } else { /* position controller disabled, reset setpoints */ - reset_sp_z = true; - reset_sp_xy = true; + reset_man_sp_z = true; + reset_man_sp_xy = true; reset_int_z = true; reset_int_xy = true; - global_pos_sp_reproject = true; - reset_auto_pos = true; + reset_mission_sp = true; + reset_auto_sp_xy = true; + reset_auto_sp_z = true; } /* reset altitude controller integral (hovering throttle) to manual throttle after manual throttle control */ diff --git a/src/modules/systemlib/pid/pid.c b/src/modules/systemlib/pid/pid.c index 739503ed4..77c952f52 100644 --- a/src/modules/systemlib/pid/pid.c +++ b/src/modules/systemlib/pid/pid.c @@ -167,20 +167,26 @@ __EXPORT float pid_calculate(PID_t *pid, float sp, float val, float val_dot, flo d = 0.0f; } - // Calculate the error integral and check for saturation - i = pid->integral + (error * dt); - - if ((pid->limit > SIGMA && (fabsf((error * pid->kp) + (i * pid->ki) + (d * pid->kd)) > pid->limit)) || - fabsf(i) > pid->intmax) { - i = pid->integral; // If saturated then do not update integral value - pid->saturated = 1; + if (pid->ki > 0.0f) { + // Calculate the error integral and check for saturation + i = pid->integral + (error * dt); + + if ((pid->limit > SIGMA && (fabsf((error * pid->kp) + (i * pid->ki) + (d * pid->kd)) > pid->limit)) || + fabsf(i) > pid->intmax) { + i = pid->integral; // If saturated then do not update integral value + pid->saturated = 1; + + } else { + if (!isfinite(i)) { + i = 0.0f; + } - } else { - if (!isfinite(i)) { - i = 0.0f; + pid->integral = i; + pid->saturated = 0; } - pid->integral = i; + } else { + i = 0.0f; pid->saturated = 0; } -- cgit v1.2.3 From 3b8039e4e009868ec7722ad559cd5b62c5f7a325 Mon Sep 17 00:00:00 2001 From: Jean Cyr Date: Wed, 11 Sep 2013 22:11:37 -0400 Subject: Implement message based receiver pairing --- src/drivers/px4io/px4io.cpp | 32 ++++++++++++++++++++++++++++--- src/modules/uORB/topics/vehicle_command.h | 3 ++- 2 files changed, 31 insertions(+), 4 deletions(-) (limited to 'src/modules') diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 78d1d3e63..c93904a3f 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -254,6 +254,7 @@ private: int _t_actuator_armed; ///< system armed control topic int _t_vehicle_control_mode;///< vehicle control mode topic int _t_param; ///< parameter update topic + int _t_vehicle_command; ///< vehicle command topic /* advertised topics */ orb_advert_t _to_input_rc; ///< rc inputs from io @@ -440,6 +441,7 @@ PX4IO::PX4IO(device::Device *interface) : _t_actuator_armed(-1), _t_vehicle_control_mode(-1), _t_param(-1), + _t_vehicle_command(-1), _to_input_rc(0), _to_actuators_effective(0), _to_outputs(0), @@ -732,16 +734,20 @@ PX4IO::task_main() _t_param = orb_subscribe(ORB_ID(parameter_update)); orb_set_interval(_t_param, 500); /* 2Hz update rate max. */ + _t_vehicle_command = orb_subscribe(ORB_ID(vehicle_command)); + orb_set_interval(_t_param, 1000); /* 1Hz update rate max. */ + if ((_t_actuators < 0) || (_t_actuator_armed < 0) || (_t_vehicle_control_mode < 0) || - (_t_param < 0)) { + (_t_param < 0) || + (_t_vehicle_command < 0)) { log("subscription(s) failed"); goto out; } /* poll descriptor */ - pollfd fds[4]; + pollfd fds[5]; fds[0].fd = _t_actuators; fds[0].events = POLLIN; fds[1].fd = _t_actuator_armed; @@ -750,8 +756,10 @@ PX4IO::task_main() fds[2].events = POLLIN; fds[3].fd = _t_param; fds[3].events = POLLIN; + fds[4].fd = _t_vehicle_command; + fds[4].events = POLLIN; - debug("ready"); + log("ready"); /* lock against the ioctl handler */ lock(); @@ -791,6 +799,24 @@ PX4IO::task_main() if ((fds[1].revents & POLLIN) || (fds[2].revents & POLLIN)) io_set_arming_state(); + /* if we have a vehicle command, handle it */ + if (fds[4].revents & POLLIN) { + struct vehicle_command_s cmd; + orb_copy(ORB_ID(vehicle_command), _t_vehicle_command, &cmd); + if ((cmd.command == VEHICLE_CMD_START_RX_PAIR) && (cmd.param1== 0.0f)) { + if (!(_status & PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED)) { + if ((cmd.param2 == 0.0f) || (cmd.param2 == 1.0f)) { + mavlink_log_info(mavlink_fd, "[IO] binding dsm%c rx", (cmd.param2 == 0.0f) == 1 ? '2' : 'x'); + ioctl(nullptr, DSM_BIND_START, (cmd.param2 == 0.0f) ? 3 : 7); + } else { + mavlink_log_info(mavlink_fd, "[IO] invalid bind type, bind request rejected"); + } + } else { + mavlink_log_info(mavlink_fd, "[IO] system armed, bind request rejected"); + } + } + } + /* * If it's time for another tick of the polling status machine, * try it now. diff --git a/src/modules/uORB/topics/vehicle_command.h b/src/modules/uORB/topics/vehicle_command.h index 31ff014de..a62e38db2 100644 --- a/src/modules/uORB/topics/vehicle_command.h +++ b/src/modules/uORB/topics/vehicle_command.h @@ -86,7 +86,8 @@ enum VEHICLE_CMD VEHICLE_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */ VEHICLE_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */ VEHICLE_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */ - VEHICLE_CMD_ENUM_END=401, /* | */ + VEHICLE_CMD_START_RX_PAIR=500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */ + VEHICLE_CMD_ENUM_END=501, /* | */ }; /** -- cgit v1.2.3 From 41610ff7dd6233853270e921828c815797fd6aeb Mon Sep 17 00:00:00 2001 From: Jean Cyr Date: Thu, 12 Sep 2013 21:36:20 -0400 Subject: DSM pairing cleanup in px4io.cpp - Simplify parameter range checking in dsm_bind_ioctl - Replace DSM magic numbers with symbolic constants --- src/drivers/drv_pwm_output.h | 3 +++ src/drivers/px4io/px4io.cpp | 26 +++++++++++++------------- src/modules/sensors/sensor_params.c | 2 +- 3 files changed, 17 insertions(+), 14 deletions(-) (limited to 'src/modules') diff --git a/src/drivers/drv_pwm_output.h b/src/drivers/drv_pwm_output.h index ec9d4ca09..94e923d71 100644 --- a/src/drivers/drv_pwm_output.h +++ b/src/drivers/drv_pwm_output.h @@ -118,6 +118,9 @@ ORB_DECLARE(output_pwm); /** start DSM bind */ #define DSM_BIND_START _IOC(_PWM_SERVO_BASE, 7) +#define DSM2_BIND_PULSES 3 /* DSM_BIND_START ioctl parameter, pulses required to start dsm2 pairing */ +#define DSMX_BIND_PULSES 7 /* DSM_BIND_START ioctl parameter, pulses required to start dsmx pairing */ + /** Power up DSM receiver */ #define DSM_BIND_POWER_UP _IOC(_PWM_SERVO_BASE, 8) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 56a294098..6e3a39aae 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -415,10 +415,9 @@ private: /** * Handle issuing dsm bind ioctl to px4io. * - * @param valid true: the dsm mode is in range - * @param isDsm2 true: dsm2m false: dsmx + * @param dsmMode 0:dsm2, 1:dsmx */ - void dsm_bind_ioctl(bool valid, bool isDsm2); + void dsm_bind_ioctl(int dsmMode); }; @@ -816,7 +815,7 @@ PX4IO::task_main() orb_copy(ORB_ID(vehicle_command), _t_vehicle_command, &cmd); // Check for a DSM pairing command if ((cmd.command == VEHICLE_CMD_START_RX_PAIR) && (cmd.param1== 0.0f)) { - dsm_bind_ioctl((cmd.param2 == 0.0f) || (cmd.param2 == 1.0f), cmd.param2 == 0.0f); + dsm_bind_ioctl((int)cmd.param2); } } @@ -857,8 +856,8 @@ PX4IO::task_main() // See if bind parameter has been set, and reset it to 0 param_get(dsm_bind_param = param_find("RC_DSM_BIND"), &dsm_bind_val); if (dsm_bind_val) { - dsm_bind_ioctl((dsm_bind_val == 1) || (dsm_bind_val == 2), dsm_bind_val == 1); - dsm_bind_val = 0; + dsm_bind_ioctl(dsm_bind_val); + dsm_bind_val = -1; param_set(dsm_bind_param, &dsm_bind_val); } @@ -1166,14 +1165,15 @@ PX4IO::io_handle_status(uint16_t status) } void -PX4IO::dsm_bind_ioctl(bool valid, bool isDsm2) +PX4IO::dsm_bind_ioctl(int dsmMode) { if (!(_status & PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED)) { - if (valid) { - mavlink_log_info(_thread_mavlink_fd, "[IO] binding dsm%c rx", isDsm2 ? '2' : 'x'); - ioctl(nullptr, DSM_BIND_START, isDsm2 ? 3 : 7); + /* 0: dsm2, 1:dsmx */ + if ((dsmMode >= 0) && (dsmMode <= 1)) { + mavlink_log_info(_thread_mavlink_fd, "[IO] binding dsm%c rx", (dsmMode == 0) ? '2' : 'x'); + ioctl(nullptr, DSM_BIND_START, (dsmMode == 0) ? DSM2_BIND_PULSES : DSMX_BIND_PULSES); } else { - mavlink_log_info(_thread_mavlink_fd, "[IO] invalid bind type, bind request rejected"); + mavlink_log_info(_thread_mavlink_fd, "[IO] invalid dsm bind mode, bind request rejected"); } } else { mavlink_log_info(_thread_mavlink_fd, "[IO] system armed, bind request rejected"); @@ -2035,9 +2035,9 @@ bind(int argc, char *argv[]) errx(0, "needs argument, use dsm2 or dsmx"); if (!strcmp(argv[2], "dsm2")) - pulses = 3; + pulses = DSM2_BIND_PULSES; else if (!strcmp(argv[2], "dsmx")) - pulses = 7; + pulses = DSMX_BIND_PULSES; else errx(1, "unknown parameter %s, use dsm2 or dsmx", argv[2]); diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c index 992abf2cc..950af2eba 100644 --- a/src/modules/sensors/sensor_params.c +++ b/src/modules/sensors/sensor_params.c @@ -166,7 +166,7 @@ PARAM_DEFINE_FLOAT(RC15_DZ, 0.0f); PARAM_DEFINE_INT32(RC_RL1_DSM_VCC, 0); /* Relay 1 controls DSM VCC */ -PARAM_DEFINE_INT32(RC_DSM_BIND, 0); /* 0 = Idle, 1 = Start DSM2 bind, 2 = Start DSMX bind */ +PARAM_DEFINE_INT32(RC_DSM_BIND, -1); /* -1 = Idle, 0 = Start DSM2 bind, 1 = Start DSMX bind */ #ifdef CONFIG_ARCH_BOARD_PX4FMU_V2 PARAM_DEFINE_FLOAT(BAT_V_SCALING, 0.0082f); -- cgit v1.2.3 From 8a70efdf43706b42e552a131e332789c114c7d4b Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sat, 14 Sep 2013 08:55:45 +0200 Subject: Beep and print message when arming is not allowed --- src/modules/commander/commander.cpp | 104 ++++++++++++++++++++++-------------- 1 file changed, 65 insertions(+), 39 deletions(-) (limited to 'src/modules') diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 5eeb018fd..a2443b0f6 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -369,7 +369,13 @@ void handle_command(struct vehicle_status_s *status, const struct safety_s *safe transition_result_t arming_res = TRANSITION_NOT_CHANGED; if (base_mode & MAV_MODE_FLAG_SAFETY_ARMED) { - arming_res = arming_state_transition(status, safety, ARMING_STATE_ARMED, armed); + if (safety->safety_switch_available && !safety->safety_off) { + print_reject_arm("NOT ARMING: Press safety switch first."); + arming_res = TRANSITION_DENIED; + + } else { + arming_res = arming_state_transition(status, safety, ARMING_STATE_ARMED, armed); + } if (arming_res == TRANSITION_CHANGED) { mavlink_log_info(mavlink_fd, "[cmd] ARMED by command"); @@ -561,7 +567,7 @@ int commander_thread_main(int argc, char *argv[]) /* flags for control apps */ struct vehicle_control_mode_s control_mode; - + /* Initialize all flags to false */ memset(&control_mode, 0, sizeof(control_mode)); @@ -1083,10 +1089,18 @@ int commander_thread_main(int argc, char *argv[]) /* check if left stick is in lower right position and we're in MANUAL mode -> arm */ if (status.arming_state == ARMING_STATE_STANDBY && - status.main_state == MAIN_STATE_MANUAL && sp_man.yaw > STICK_ON_OFF_LIMIT && sp_man.throttle < STICK_THRUST_RANGE * 0.1f) { if (stick_on_counter > STICK_ON_OFF_COUNTER_LIMIT) { - res = arming_state_transition(&status, &safety, ARMING_STATE_ARMED, &armed); + if (safety.safety_switch_available && !safety.safety_off) { + print_reject_arm("NOT ARMING: Press safety switch first."); + + } else if (status.main_state != MAIN_STATE_MANUAL) { + print_reject_arm("NOT ARMING: Switch to MANUAL mode first."); + + } else { + res = arming_state_transition(&status, &safety, ARMING_STATE_ARMED, &armed); + } + stick_on_counter = 0; } else { @@ -1106,15 +1120,8 @@ int commander_thread_main(int argc, char *argv[]) } } else if (res == TRANSITION_DENIED) { - /* DENIED here indicates safety switch not pressed */ - - if (!(!safety.safety_switch_available || safety.safety_off)) { - print_reject_arm("NOT ARMING: Press safety switch first."); - - } else { - warnx("ERROR: main denied: arm %d main %d mode_sw %d", status.arming_state, status.main_state, status.mode_switch); - mavlink_log_critical(mavlink_fd, "[cmd] ERROR: main denied: arm %d main %d mode_sw %d", status.arming_state, status.main_state, status.mode_switch); - } + warnx("ERROR: main denied: arm %d main %d mode_sw %d", status.arming_state, status.main_state, status.mode_switch); + mavlink_log_critical(mavlink_fd, "[cmd] ERROR: main denied: arm %d main %d mode_sw %d", status.arming_state, status.main_state, status.mode_switch); } /* fill current_status according to mode switches */ @@ -1228,6 +1235,7 @@ int commander_thread_main(int argc, char *argv[]) /* wait for threads to complete */ ret = pthread_join(commander_low_prio_thread, NULL); + if (ret) { warn("join failed", ret); } @@ -1295,8 +1303,10 @@ toggle_status_leds(vehicle_status_s *status, actuator_armed_s *armed, bool chang if (armed->armed) { rgbled_set_mode(RGBLED_MODE_ON); + } else if (armed->ready_to_arm) { rgbled_set_mode(RGBLED_MODE_BREATHE); + } else { rgbled_set_mode(RGBLED_MODE_BLINK_FAST); } @@ -1304,29 +1314,35 @@ toggle_status_leds(vehicle_status_s *status, actuator_armed_s *armed, bool chang if (status->battery_warning != VEHICLE_BATTERY_WARNING_NONE) { switch (status->battery_warning) { - case VEHICLE_BATTERY_WARNING_LOW: - rgbled_set_color(RGBLED_COLOR_YELLOW); - break; - case VEHICLE_BATTERY_WARNING_CRITICAL: - rgbled_set_color(RGBLED_COLOR_AMBER); - break; - default: - break; + case VEHICLE_BATTERY_WARNING_LOW: + rgbled_set_color(RGBLED_COLOR_YELLOW); + break; + + case VEHICLE_BATTERY_WARNING_CRITICAL: + rgbled_set_color(RGBLED_COLOR_AMBER); + break; + + default: + break; } + } else { switch (status->main_state) { - case MAIN_STATE_MANUAL: - rgbled_set_color(RGBLED_COLOR_WHITE); - break; - case MAIN_STATE_SEATBELT: - case MAIN_STATE_EASY: - rgbled_set_color(RGBLED_COLOR_GREEN); - break; - case MAIN_STATE_AUTO: - rgbled_set_color(RGBLED_COLOR_BLUE); - break; - default: - break; + case MAIN_STATE_MANUAL: + rgbled_set_color(RGBLED_COLOR_WHITE); + break; + + case MAIN_STATE_SEATBELT: + case MAIN_STATE_EASY: + rgbled_set_color(RGBLED_COLOR_GREEN); + break; + + case MAIN_STATE_AUTO: + rgbled_set_color(RGBLED_COLOR_BLUE); + break; + + default: + break; } } @@ -1497,16 +1513,18 @@ check_navigation_state_machine(struct vehicle_status_s *status, struct vehicle_c return TRANSITION_NOT_CHANGED; } } + if (status->navigation_state != NAVIGATION_STATE_AUTO_TAKEOFF && - status->navigation_state != NAVIGATION_STATE_AUTO_LOITER && - status->navigation_state != NAVIGATION_STATE_AUTO_MISSION && - status->navigation_state != NAVIGATION_STATE_AUTO_RTL) { + status->navigation_state != NAVIGATION_STATE_AUTO_LOITER && + status->navigation_state != NAVIGATION_STATE_AUTO_MISSION && + status->navigation_state != NAVIGATION_STATE_AUTO_RTL) { /* possibly on ground, switch to TAKEOFF if needed */ if (local_pos->z > -takeoff_alt || status->condition_landed) { res = navigation_state_transition(status, NAVIGATION_STATE_AUTO_TAKEOFF, control_mode); return res; } } + /* switch to AUTO mode */ if (status->rc_signal_found_once && !status->rc_signal_lost) { /* act depending on switches when manual control enabled */ @@ -1524,18 +1542,20 @@ check_navigation_state_machine(struct vehicle_status_s *status, struct vehicle_c res = navigation_state_transition(status, NAVIGATION_STATE_AUTO_LOITER, control_mode); } } + } else { /* switch to MISSION when no RC control and first time in some AUTO mode */ if (status->navigation_state == NAVIGATION_STATE_AUTO_LOITER || - status->navigation_state == NAVIGATION_STATE_AUTO_MISSION || - status->navigation_state == NAVIGATION_STATE_AUTO_RTL || - status->navigation_state == NAVIGATION_STATE_AUTO_LAND) { + status->navigation_state == NAVIGATION_STATE_AUTO_MISSION || + status->navigation_state == NAVIGATION_STATE_AUTO_RTL || + status->navigation_state == NAVIGATION_STATE_AUTO_LAND) { res = TRANSITION_NOT_CHANGED; } else { res = navigation_state_transition(status, NAVIGATION_STATE_AUTO_MISSION, control_mode); } } + } else { /* disarmed, always switch to AUTO_READY */ res = navigation_state_transition(status, NAVIGATION_STATE_AUTO_READY, control_mode); @@ -1762,35 +1782,41 @@ void *commander_low_prio_loop(void *arg) if (((int)(cmd.param1)) == 0) { int ret = param_load_default(); + if (ret == OK) { mavlink_log_info(mavlink_fd, "[cmd] parameters loaded"); answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED); } else { mavlink_log_critical(mavlink_fd, "[cmd] parameters load ERROR"); + /* convenience as many parts of NuttX use negative errno */ if (ret < 0) ret = -ret; if (ret < 1000) mavlink_log_critical(mavlink_fd, "[cmd] %s", strerror(ret)); + answer_command(cmd, VEHICLE_CMD_RESULT_FAILED); } } else if (((int)(cmd.param1)) == 1) { int ret = param_save_default(); + if (ret == OK) { mavlink_log_info(mavlink_fd, "[cmd] parameters saved"); answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED); } else { mavlink_log_critical(mavlink_fd, "[cmd] parameters save error"); + /* convenience as many parts of NuttX use negative errno */ if (ret < 0) ret = -ret; if (ret < 1000) mavlink_log_critical(mavlink_fd, "[cmd] %s", strerror(ret)); + answer_command(cmd, VEHICLE_CMD_RESULT_FAILED); } } -- cgit v1.2.3 From 2fbd23cf6ea535adccdeacfd12af731570524fd4 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sat, 14 Sep 2013 17:31:58 +0200 Subject: sdlog2: position & velocity valid, postion global and landed flags added to LPOS, some refactoring --- .../position_estimator_inav/position_estimator_inav_main.c | 10 +++++----- src/modules/sdlog2/sdlog2.c | 3 +++ src/modules/sdlog2/sdlog2_messages.h | 5 ++++- src/modules/uORB/topics/vehicle_local_position.h | 4 ++-- 4 files changed, 14 insertions(+), 8 deletions(-) (limited to 'src/modules') diff --git a/src/modules/position_estimator_inav/position_estimator_inav_main.c b/src/modules/position_estimator_inav/position_estimator_inav_main.c index 932f61088..10007bf96 100644 --- a/src/modules/position_estimator_inav/position_estimator_inav_main.c +++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c @@ -259,7 +259,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) local_pos.ref_timestamp = hrt_absolute_time(); local_pos.z_valid = true; local_pos.v_z_valid = true; - local_pos.global_z = true; + local_pos.z_global = true; } } } @@ -597,7 +597,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) local_pos.timestamp = t; local_pos.xy_valid = can_estimate_xy && gps_valid; local_pos.v_xy_valid = can_estimate_xy; - local_pos.global_xy = local_pos.xy_valid && gps_valid; // will make sense when local position sources (e.g. vicon) will be implemented + local_pos.xy_global = local_pos.xy_valid && gps_valid; // will make sense when local position sources (e.g. vicon) will be implemented local_pos.x = x_est[0]; local_pos.vx = x_est[1]; local_pos.y = y_est[0]; @@ -610,9 +610,9 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) orb_publish(ORB_ID(vehicle_local_position), vehicle_local_position_pub, &local_pos); /* publish global position */ - global_pos.valid = local_pos.global_xy; + global_pos.valid = local_pos.xy_global; - if (local_pos.global_xy) { + if (local_pos.xy_global) { double est_lat, est_lon; map_projection_reproject(local_pos.x, local_pos.y, &est_lat, &est_lon); global_pos.lat = (int32_t)(est_lat * 1e7); @@ -630,7 +630,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) global_pos.relative_alt = -local_pos.z; } - if (local_pos.global_z) { + if (local_pos.z_global) { global_pos.alt = local_pos.ref_alt - local_pos.z; } diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index e83fb7dd3..ec8033202 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -1046,6 +1046,9 @@ int sdlog2_thread_main(int argc, char *argv[]) log_msg.body.log_LPOS.ref_lat = buf.local_pos.ref_lat; log_msg.body.log_LPOS.ref_lon = buf.local_pos.ref_lon; log_msg.body.log_LPOS.ref_alt = buf.local_pos.ref_alt; + log_msg.body.log_LPOS.xy_flags = (buf.local_pos.xy_valid ? 1 : 0) | (buf.local_pos.v_xy_valid ? 2 : 0) | (buf.local_pos.xy_global ? 8 : 0); + log_msg.body.log_LPOS.z_flags = (buf.local_pos.z_valid ? 1 : 0) | (buf.local_pos.v_z_valid ? 2 : 0) | (buf.local_pos.z_global ? 8 : 0); + log_msg.body.log_LPOS.landed = buf.local_pos.landed; LOGBUFFER_WRITE_AND_COUNT(LPOS); } diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h index 1343bb3d0..0e88da054 100644 --- a/src/modules/sdlog2/sdlog2_messages.h +++ b/src/modules/sdlog2/sdlog2_messages.h @@ -109,6 +109,9 @@ struct log_LPOS_s { int32_t ref_lat; int32_t ref_lon; float ref_alt; + uint8_t xy_flags; + uint8_t z_flags; + uint8_t landed; }; /* --- LPSP - LOCAL POSITION SETPOINT --- */ @@ -278,7 +281,7 @@ static const struct log_format_s log_formats[] = { LOG_FORMAT(ATSP, "ffff", "RollSP,PitchSP,YawSP,ThrustSP"), LOG_FORMAT(IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"), LOG_FORMAT(SENS, "ffff", "BaroPres,BaroAlt,BaroTemp,DiffPres"), - LOG_FORMAT(LPOS, "ffffffLLf", "X,Y,Z,VX,VY,VZ,RefLat,RefLon,RefAlt"), + LOG_FORMAT(LPOS, "ffffffLLfBBB", "X,Y,Z,VX,VY,VZ,RefLat,RefLon,RefAlt,XYFlags,ZFlags,Landed"), LOG_FORMAT(LPSP, "ffff", "X,Y,Z,Yaw"), LOG_FORMAT(GPS, "QBffLLfffff", "GPSTime,FixType,EPH,EPV,Lat,Lon,Alt,VelN,VelE,VelD,Cog"), LOG_FORMAT(ATTC, "ffff", "Roll,Pitch,Yaw,Thrust"), diff --git a/src/modules/uORB/topics/vehicle_local_position.h b/src/modules/uORB/topics/vehicle_local_position.h index 31a0e632b..427153782 100644 --- a/src/modules/uORB/topics/vehicle_local_position.h +++ b/src/modules/uORB/topics/vehicle_local_position.h @@ -70,8 +70,8 @@ struct vehicle_local_position_s /* Heading */ float yaw; /* Reference position in GPS / WGS84 frame */ - bool global_xy; /**< true if position (x, y) is valid and has valid global reference (ref_lat, ref_lon) */ - bool global_z; /**< true if z is valid and has valid global reference (ref_alt) */ + bool xy_global; /**< true if position (x, y) is valid and has valid global reference (ref_lat, ref_lon) */ + bool z_global; /**< true if z is valid and has valid global reference (ref_alt) */ uint64_t ref_timestamp; /**< Time when reference position was set */ int32_t ref_lat; /**< Reference point latitude in 1E7 degrees */ int32_t ref_lon; /**< Reference point longitude in 1E7 degrees */ -- cgit v1.2.3 From 1a641b791dd3802571e56521b7d13585c07061ef Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 16 Sep 2013 11:33:29 +0900 Subject: tone_alarm: more device paths replaced with #define --- src/modules/commander/commander_helper.cpp | 2 +- src/systemcmds/preflight_check/preflight_check.c | 2 +- src/systemcmds/tests/test_hrt.c | 4 ++-- 3 files changed, 4 insertions(+), 4 deletions(-) (limited to 'src/modules') diff --git a/src/modules/commander/commander_helper.cpp b/src/modules/commander/commander_helper.cpp index 7feace2b4..017499cb5 100644 --- a/src/modules/commander/commander_helper.cpp +++ b/src/modules/commander/commander_helper.cpp @@ -82,7 +82,7 @@ static int buzzer; int buzzer_init() { - buzzer = open("/dev/tone_alarm", O_WRONLY); + buzzer = open(TONEALARM_DEVICE_PATH, O_WRONLY); if (buzzer < 0) { warnx("Buzzer: open fail\n"); diff --git a/src/systemcmds/preflight_check/preflight_check.c b/src/systemcmds/preflight_check/preflight_check.c index f5bd01ce8..e9c5f1a2c 100644 --- a/src/systemcmds/preflight_check/preflight_check.c +++ b/src/systemcmds/preflight_check/preflight_check.c @@ -163,7 +163,7 @@ system_eval: warnx("PREFLIGHT CHECK ERROR! TRIGGERING ALARM"); fflush(stderr); - int buzzer = open("/dev/tone_alarm", O_WRONLY); + int buzzer = open(TONEALARM_DEVICE_PATH, O_WRONLY); int leds = open(LED_DEVICE_PATH, 0); if (leds < 0) { diff --git a/src/systemcmds/tests/test_hrt.c b/src/systemcmds/tests/test_hrt.c index ba6b86adb..5690997a9 100644 --- a/src/systemcmds/tests/test_hrt.c +++ b/src/systemcmds/tests/test_hrt.c @@ -124,10 +124,10 @@ int test_tone(int argc, char *argv[]) int fd, result; unsigned long tone; - fd = open("/dev/tone_alarm", O_WRONLY); + fd = open(TONEALARM_DEVICE_PATH, O_WRONLY); if (fd < 0) { - printf("failed opening /dev/tone_alarm\n"); + printf("failed opening " TONEALARM_DEVICE_PATH "\n"); goto out; } -- cgit v1.2.3