void *multirotor_attitude_control_thread_main() { /* welcome user */ fprintf (stdout, "Multirotor attitude controller started\n"); fflush(stdout); int i; bool_t updated, rates_sp_updated, reset_integral; float rates[3]; /* store last control mode to detect mode switches */ bool_t control_yaw_position = 1 /* true */; bool_t reset_yaw_sp = 1 /* true */; /* declare and safely initialize all structs */ struct parameter_update_s update; struct vehicle_attitude_s att; memset(&att, 0, sizeof(att)); struct vehicle_attitude_setpoint_s att_sp; memset(&att_sp, 0, sizeof(att_sp)); struct offboard_control_setpoint_s offboard_sp; memset(&offboard_sp, 0, sizeof(offboard_sp)); struct vehicle_control_flags_s control_flags; memset(&control_flags, 0, sizeof(control_flags)); struct manual_control_setpoint_s manual; memset(&manual, 0, sizeof(manual)); struct sensor_combined_s sensor; memset(&sensor, 0, sizeof(sensor)); struct vehicle_rates_setpoint_s rates_sp; memset(&rates_sp, 0, sizeof(rates_sp)); struct vehicle_status_s status; memset(&status, 0, sizeof(status)); struct actuator_controls_s actuators; memset(&actuators, 0, sizeof(actuators)); /* subscribe */ orb_subscr_t vehicle_attitude_sub = orb_subscribe(ORB_ID(vehicle_attitude)); if (vehicle_attitude_sub < 0) { fprintf (stderr, "Attitude controller thread failed to subscribe to vehicle_attitude topic\n"); exit(-1); } orb_subscr_t parameter_update_sub = orb_subscribe(ORB_ID(parameter_update)); if (parameter_update_sub < 0) { fprintf (stderr, "Attitude controller thread failed to subscribe to parameter_update topic\n"); exit(-1); } orb_subscr_t vehicle_attitude_setpoint_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint)); if (vehicle_attitude_setpoint_sub < 0) { fprintf (stderr, "Attitude controller thread failed to subscribe to vehicle_attitude_setpoint topic\n"); exit(-1); } orb_subscr_t offboard_control_setpoint_sub = orb_subscribe(ORB_ID(offboard_control_setpoint)); if (offboard_control_setpoint_sub < 0) { fprintf (stderr, "Attitude controller thread failed to subscribe to offboard_control_setpoint topic\n"); exit(-1); } orb_subscr_t vehicle_control_flags_sub = orb_subscribe(ORB_ID(vehicle_control_flags)); if (vehicle_control_flags_sub < 0) { fprintf (stderr, "Attitude controller thread failed to subscribe to vehicle_control_flags topic\n"); exit(-1); } orb_subscr_t manual_control_setpoint_sub = orb_subscribe(ORB_ID(manual_control_setpoint)); if (manual_control_setpoint_sub < 0) { fprintf (stderr, "Attitude controller thread failed to subscribe to manual_control_setpoint topic\n"); exit(-1); } orb_subscr_t sensor_combined_sub = orb_subscribe(ORB_ID(sensor_combined)); if (sensor_combined_sub < 0) { fprintf (stderr, "Attitude controller thread failed to subscribe to sensor_combined topic\n"); exit(-1); } orb_subscr_t vehicle_rates_setpoint_sub = orb_subscribe(ORB_ID(vehicle_rates_setpoint)); if (vehicle_rates_setpoint_sub < 0) { fprintf (stderr, "Attitude controller thread failed to subscribe to vehicle_rates_setpoint topic\n"); exit(-1); } orb_subscr_t vehicle_status_sub = orb_subscribe(ORB_ID(vehicle_status)); if (vehicle_status_sub < 0) { fprintf (stderr, "Attitude controller thread failed to subscribe to vehicle_status topic\n"); exit(-1); } /* publish actuator controls */ for (i = 0; i < NUM_ACTUATOR_CONTROLS; i++) { actuators.control[i] = 0.0f; } orb_advert_t actuator_pub = orb_advertise(ORB_ID_VEHICLE_ATTITUDE_CONTROLS); if (actuator_pub == -1) { fprintf (stderr, "Comunicator thread failed to advertise the actutor_controls topic\n"); exit (-1); } orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators); orb_advert_t att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint)); if (att_sp_pub == -1) { fprintf (stderr, "Comunicator thread failed to advertise the vehicle_attitude_setpoint topic\n"); exit (-1); } orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp); orb_advert_t rates_sp_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint)); if (rates_sp_pub == -1) { fprintf (stderr, "Comunicator thread failed to advertise the vehicle_rates_setpoint topic\n"); exit (-1); } orb_publish(ORB_ID(vehicle_rates_setpoint), rates_sp_pub, &rates_sp); while (!_shutdown_all_systems) { /* wait for a sensor update, check for exit condition every 500 ms */ updated = orb_poll(ORB_ID(vehicle_attitude), vehicle_attitude_sub, 500000); /* timed out - periodic check for _shutdown_all_systems, etc. */ if (!updated) continue; /* this is undesirable but not much we can do - might want to flag unhappy status */ if (updated < 0) { fprintf (stderr, "Attitude controller failed to poll vehicle attitude\n"); continue; } /* only run controller if attitude changed */ /* attitude */ orb_copy(ORB_ID(vehicle_attitude), vehicle_attitude_sub, &att); /* parameters */ updated = orb_check (ORB_ID(parameter_update), parameter_update_sub); if (updated) { orb_copy(ORB_ID(parameter_update), parameter_update_sub, &update); /* update parameters */ } /* control mode */ updated = orb_check (ORB_ID(vehicle_control_flags), vehicle_control_flags_sub); if (updated) { orb_copy(ORB_ID(vehicle_control_flags), vehicle_control_flags_sub, &control_flags); } /* manual control setpoint */ updated = orb_check (ORB_ID(manual_control_setpoint), manual_control_setpoint_sub); if (updated) { orb_copy(ORB_ID(manual_control_setpoint), manual_control_setpoint_sub, &manual); } /* attitude setpoint */ updated = orb_check (ORB_ID(vehicle_attitude_setpoint), vehicle_attitude_setpoint_sub); if (updated) { orb_copy(ORB_ID(vehicle_attitude_setpoint), vehicle_attitude_setpoint_sub, &att_sp); } /* offboard control setpoint */ updated = orb_check (ORB_ID(offboard_control_setpoint), offboard_control_setpoint_sub); if (updated) { orb_copy(ORB_ID(offboard_control_setpoint), offboard_control_setpoint_sub, &offboard_sp); } /* vehicle status */ updated = orb_check (ORB_ID(vehicle_status), vehicle_status_sub); if (updated) { orb_copy(ORB_ID(vehicle_status), vehicle_status_sub, &status); } /* sensors */ updated = orb_check (ORB_ID(sensor_combined), sensor_combined_sub); if (updated) { orb_copy(ORB_ID(sensor_combined), sensor_combined_sub, &sensor); } /* set flag to safe value */ control_yaw_position = 1 /* true */; /* reset yaw setpoint if not armed */ if (!control_flags.flag_armed) { reset_yaw_sp = 1 /* true */; } /* define which input is the dominating control input */ if (control_flags.flag_control_offboard_enabled) { /* offboard inputs */ if (offboard_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_RATES) { rates_sp.roll = offboard_sp.p1; rates_sp.pitch = offboard_sp.p2; rates_sp.yaw = offboard_sp.p3; rates_sp.thrust = offboard_sp.p4; rates_sp.timestamp = get_absolute_time(); orb_publish(ORB_ID(vehicle_rates_setpoint), rates_sp_pub, &rates_sp); } else if (offboard_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE) { att_sp.roll_body = offboard_sp.p1; att_sp.pitch_body = offboard_sp.p2; att_sp.yaw_body = offboard_sp.p3; att_sp.thrust = offboard_sp.p4; att_sp.timestamp = get_absolute_time(); /* publish the result to the vehicle actuators */ orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp); } /* reset yaw setpoint after offboard control */ reset_yaw_sp = 1 /* true */; } else if (control_flags.flag_control_manual_enabled) { /* manual input */ if (control_flags.flag_control_attitude_enabled) { /* control attitude, update attitude setpoint depending on mode */ if (att_sp.thrust < 0.1f) { /* no thrust, don't try to control yaw */ rates_sp.yaw = 0.0f; control_yaw_position = 0 /* false */; if (status.condition_landed) { /* reset yaw setpoint if on ground */ reset_yaw_sp = 1 /* true */; } } else { /* only move yaw setpoint if manual input is != 0 */ if (manual.yaw < -yaw_deadzone || yaw_deadzone < manual.yaw) { /* control yaw rate */ control_yaw_position = 0 /* false */; rates_sp.yaw = manual.yaw; reset_yaw_sp = 1 /* true */; // has no effect on control, just for beautiful log } else { control_yaw_position = 1 /* true */; } } if (!control_flags.flag_control_velocity_enabled) { /* update attitude setpoint if not in position control mode */ att_sp.roll_body = manual.roll; att_sp.pitch_body = manual.pitch; if (!control_flags.flag_control_climb_rate_enabled) { /* pass throttle directly if not in altitude control mode */ att_sp.thrust = manual.thrust; } } /* reset yaw setpint to current position if needed */ if (reset_yaw_sp) { att_sp.yaw_body = att.yaw; reset_yaw_sp = 0 /* false */; } /*if (motor_test_mode) { printf("testmode"); att_sp.roll_body = 0.0f; att_sp.pitch_body = 0.0f; att_sp.yaw_body = 0.0f; att_sp.thrust = 0.1f; }*/ att_sp.timestamp = get_absolute_time(); /* publish the attitude setpoint */ orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp); } else { /* manual rate inputs (ACRO), from RC control or joystick */ if (control_flags.flag_control_rates_enabled) { rates_sp.roll = manual.roll; rates_sp.pitch = manual.pitch; rates_sp.yaw = manual.yaw; rates_sp.thrust = manual.thrust; rates_sp.timestamp = get_absolute_time(); } /* reset yaw setpoint after ACRO */ reset_yaw_sp = 1 /* true */; } } else { if (!control_flags.flag_control_auto_enabled) { /* no control, try to stay on place */ if (!control_flags.flag_control_velocity_enabled) { /* no velocity control, reset attitude setpoint */ att_sp.roll_body = 0.0f; att_sp.pitch_body = 0.0f; att_sp.timestamp = get_absolute_time(); orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp); } } /* reset yaw setpoint after non-manual control */ reset_yaw_sp = 1 /* true */; } /* check if we should we reset integrals */ reset_integral = !control_flags.flag_armed || att_sp.thrust < 0.1f; // TODO use landed status instead of throttle /* run attitude controller if needed */ if (control_flags.flag_control_attitude_enabled) { multirotor_control_attitude(&att_sp, &att, &rates_sp, control_yaw_position, reset_integral); orb_publish(ORB_ID(vehicle_rates_setpoint), rates_sp_pub, &rates_sp); } /* run rates controller if needed */ if (control_flags.flag_control_rates_enabled) { /* get current rate setpoint */ rates_sp_updated = orb_check (ORB_ID(vehicle_rates_setpoint), vehicle_rates_setpoint_sub); if (rates_sp_updated) { orb_copy(ORB_ID(vehicle_rates_setpoint), vehicle_rates_setpoint_sub, &rates_sp); } /* apply controller */ rates[0] = att.roll_rate; rates[1] = att.pitch_rate; rates[2] = att.yaw_rate; multirotor_control_rates(&rates_sp, rates, &actuators, reset_integral); } else { /* rates controller disabled, set actuators to zero for safety */ actuators.control[0] = 0.0f; actuators.control[1] = 0.0f; actuators.control[2] = 0.0f; actuators.control[3] = 0.0f; } /* fill in manual control values */ actuators.control[4] = manual.flaps; //actuators.control[5] = manual.aux1; //actuators.control[6] = manual.aux2; //actuators.control[7] = manual.aux3; orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators); } fprintf (stdout, "INFO: Attitude controller exiting, disarming motors\n"); fflush (stdout); /* kill all outputs */ for (i = 0; i < NUM_ACTUATOR_CONTROLS; i++) actuators.control[i] = 0.0f; orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators); /* * do unsubscriptions */ orb_unsubscribe(ORB_ID(vehicle_attitude), vehicle_attitude_sub, pthread_self()); orb_unsubscribe(ORB_ID(parameter_update), parameter_update_sub, pthread_self()); orb_unsubscribe(ORB_ID(vehicle_attitude_setpoint), vehicle_attitude_setpoint_sub, pthread_self()); orb_unsubscribe(ORB_ID(offboard_control_setpoint), offboard_control_setpoint_sub, pthread_self()); orb_unsubscribe(ORB_ID(vehicle_control_flags), vehicle_control_flags_sub, pthread_self()); orb_unsubscribe(ORB_ID(manual_control_setpoint), manual_control_setpoint_sub, pthread_self()); orb_unsubscribe(ORB_ID(sensor_combined), sensor_combined_sub, pthread_self()); orb_unsubscribe(ORB_ID(vehicle_rates_setpoint), vehicle_rates_setpoint_sub, pthread_self()); orb_unsubscribe(ORB_ID(vehicle_status), vehicle_status_sub, pthread_self()); /* * do unadvertises */ orb_unadvertise(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, pthread_self()); orb_unadvertise(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, pthread_self()); orb_unadvertise(ORB_ID(vehicle_rates_setpoint), rates_sp_pub, pthread_self()); return 0; }
void FixedwingAttitudeControl::task_main() { /* * do subscriptions */ _att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint)); _att_sub = orb_subscribe(ORB_ID(vehicle_attitude)); _accel_sub = orb_subscribe_multi(ORB_ID(sensor_accel), 0); _airspeed_sub = orb_subscribe(ORB_ID(airspeed)); _vcontrol_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode)); _params_sub = orb_subscribe(ORB_ID(parameter_update)); _manual_sub = orb_subscribe(ORB_ID(manual_control_setpoint)); _global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position)); _vehicle_status_sub = orb_subscribe(ORB_ID(vehicle_status)); /* rate limit vehicle status updates to 5Hz */ orb_set_interval(_vcontrol_mode_sub, 200); /* do not limit the attitude updates in order to minimize latency. * actuator outputs are still limited by the individual drivers * properly to not saturate IO or physical limitations */ parameters_update(); /* get an initial update for all sensor and status data */ vehicle_airspeed_poll(); vehicle_setpoint_poll(); vehicle_accel_poll(); vehicle_control_mode_poll(); vehicle_manual_poll(); vehicle_status_poll(); /* wakeup source(s) */ struct pollfd fds[2]; /* Setup of loop */ fds[0].fd = _params_sub; fds[0].events = POLLIN; fds[1].fd = _att_sub; fds[1].events = POLLIN; _task_running = true; while (!_task_should_exit) { static int loop_counter = 0; /* wait for up to 500ms for data */ int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100); /* timed out - periodic check for _task_should_exit, etc. */ if (pret == 0) continue; /* this is undesirable but not much we can do - might want to flag unhappy status */ if (pret < 0) { warn("poll error %d, %d", pret, errno); continue; } perf_begin(_loop_perf); /* only update parameters if they changed */ if (fds[0].revents & POLLIN) { /* read from param to clear updated flag */ struct parameter_update_s update; orb_copy(ORB_ID(parameter_update), _params_sub, &update); /* update parameters from storage */ parameters_update(); } /* only run controller if attitude changed */ if (fds[1].revents & POLLIN) { static uint64_t last_run = 0; float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f; last_run = hrt_absolute_time(); /* guard against too large deltaT's */ if (deltaT > 1.0f) deltaT = 0.01f; /* load local copies */ orb_copy(ORB_ID(vehicle_attitude), _att_sub, &_att); if (_vehicle_status.is_vtol && _parameters.vtol_type == 0) { /* vehicle is a tailsitter, we need to modify the estimated attitude for fw mode * * Since the VTOL airframe is initialized as a multicopter we need to * modify the estimated attitude for the fixed wing operation. * Since the neutral position of the vehicle in fixed wing mode is -90 degrees rotated around * the pitch axis compared to the neutral position of the vehicle in multicopter mode * we need to swap the roll and the yaw axis (1st and 3rd column) in the rotation matrix. * Additionally, in order to get the correct sign of the pitch, we need to multiply * the new x axis of the rotation matrix with -1 * * original: modified: * * Rxx Ryx Rzx -Rzx Ryx Rxx * Rxy Ryy Rzy -Rzy Ryy Rxy * Rxz Ryz Rzz -Rzz Ryz Rxz * */ math::Matrix<3, 3> R; //original rotation matrix math::Matrix<3, 3> R_adapted; //modified rotation matrix R.set(_att.R); R_adapted.set(_att.R); /* move z to x */ R_adapted(0, 0) = R(0, 2); R_adapted(1, 0) = R(1, 2); R_adapted(2, 0) = R(2, 2); /* move x to z */ R_adapted(0, 2) = R(0, 0); R_adapted(1, 2) = R(1, 0); R_adapted(2, 2) = R(2, 0); /* change direction of pitch (convert to right handed system) */ R_adapted(0, 0) = -R_adapted(0, 0); R_adapted(1, 0) = -R_adapted(1, 0); R_adapted(2, 0) = -R_adapted(2, 0); math::Vector<3> euler_angles; //adapted euler angles for fixed wing operation euler_angles = R_adapted.to_euler(); /* fill in new attitude data */ _att.roll = euler_angles(0); _att.pitch = euler_angles(1); _att.yaw = euler_angles(2); PX4_R(_att.R, 0, 0) = R_adapted(0, 0); PX4_R(_att.R, 0, 1) = R_adapted(0, 1); PX4_R(_att.R, 0, 2) = R_adapted(0, 2); PX4_R(_att.R, 1, 0) = R_adapted(1, 0); PX4_R(_att.R, 1, 1) = R_adapted(1, 1); PX4_R(_att.R, 1, 2) = R_adapted(1, 2); PX4_R(_att.R, 2, 0) = R_adapted(2, 0); PX4_R(_att.R, 2, 1) = R_adapted(2, 1); PX4_R(_att.R, 2, 2) = R_adapted(2, 2); /* lastly, roll- and yawspeed have to be swaped */ float helper = _att.rollspeed; _att.rollspeed = -_att.yawspeed; _att.yawspeed = helper; } vehicle_airspeed_poll(); vehicle_setpoint_poll(); vehicle_accel_poll(); vehicle_control_mode_poll(); vehicle_manual_poll(); global_pos_poll(); vehicle_status_poll(); /* lock integrator until control is started */ bool lock_integrator; if (_vcontrol_mode.flag_control_attitude_enabled && !_vehicle_status.is_rotary_wing) { lock_integrator = false; } else { lock_integrator = true; } /* Simple handling of failsafe: deploy parachute if failsafe is on */ if (_vcontrol_mode.flag_control_termination_enabled) { _actuators_airframe.control[7] = 1.0f; //warnx("_actuators_airframe.control[1] = 1.0f;"); } else { _actuators_airframe.control[7] = 0.0f; //warnx("_actuators_airframe.control[1] = -1.0f;"); } /* if we are in rotary wing mode, do nothing */ if (_vehicle_status.is_rotary_wing) { continue; } /* default flaps to center */ float flaps_control = 0.0f; /* map flaps by default to manual if valid */ if (isfinite(_manual.flaps)) { flaps_control = _manual.flaps; } /* decide if in stabilized or full manual control */ if (_vcontrol_mode.flag_control_attitude_enabled) { /* scale around tuning airspeed */ float airspeed; /* if airspeed is not updating, we assume the normal average speed */ if (bool nonfinite = !isfinite(_airspeed.true_airspeed_m_s) || hrt_elapsed_time(&_airspeed.timestamp) > 1e6) { airspeed = _parameters.airspeed_trim; if (nonfinite) { perf_count(_nonfinite_input_perf); } } else { /* prevent numerical drama by requiring 0.5 m/s minimal speed */ airspeed = math::max(0.5f, _airspeed.true_airspeed_m_s); } /* * For scaling our actuators using anything less than the min (close to stall) * speed doesn't make any sense - its the strongest reasonable deflection we * want to do in flight and its the baseline a human pilot would choose. * * Forcing the scaling to this value allows reasonable handheld tests. */ float airspeed_scaling = _parameters.airspeed_trim / ((airspeed < _parameters.airspeed_min) ? _parameters.airspeed_min : airspeed); float roll_sp = _parameters.rollsp_offset_rad; float pitch_sp = _parameters.pitchsp_offset_rad; float yaw_manual = 0.0f; float throttle_sp = 0.0f; /* Read attitude setpoint from uorb if * - velocity control or position control is enabled (pos controller is running) * - manual control is disabled (another app may send the setpoint, but it should * for sure not be set from the remote control values) */ if (_vcontrol_mode.flag_control_auto_enabled || !_vcontrol_mode.flag_control_manual_enabled) { /* read in attitude setpoint from attitude setpoint uorb topic */ roll_sp = _att_sp.roll_body + _parameters.rollsp_offset_rad; pitch_sp = _att_sp.pitch_body + _parameters.pitchsp_offset_rad; throttle_sp = _att_sp.thrust; /* reset integrals where needed */ if (_att_sp.roll_reset_integral) { _roll_ctrl.reset_integrator(); } if (_att_sp.pitch_reset_integral) { _pitch_ctrl.reset_integrator(); } if (_att_sp.yaw_reset_integral) { _yaw_ctrl.reset_integrator(); } } else if (_vcontrol_mode.flag_control_velocity_enabled) { /* the pilot does not want to change direction, * take straight attitude setpoint from position controller */ if (fabsf(_manual.y) < 0.01f && fabsf(_att.roll) < 0.2f) { roll_sp = _att_sp.roll_body + _parameters.rollsp_offset_rad; } else { roll_sp = (_manual.y * _parameters.man_roll_max) + _parameters.rollsp_offset_rad; } pitch_sp = _att_sp.pitch_body + _parameters.pitchsp_offset_rad; throttle_sp = _att_sp.thrust; /* reset integrals where needed */ if (_att_sp.roll_reset_integral) { _roll_ctrl.reset_integrator(); } if (_att_sp.pitch_reset_integral) { _pitch_ctrl.reset_integrator(); } if (_att_sp.yaw_reset_integral) { _yaw_ctrl.reset_integrator(); } } else if (_vcontrol_mode.flag_control_altitude_enabled) { /* * Velocity should be controlled and manual is enabled. */ roll_sp = (_manual.y * _parameters.man_roll_max) + _parameters.rollsp_offset_rad; pitch_sp = _att_sp.pitch_body + _parameters.pitchsp_offset_rad; throttle_sp = _att_sp.thrust; /* reset integrals where needed */ if (_att_sp.roll_reset_integral) { _roll_ctrl.reset_integrator(); } if (_att_sp.pitch_reset_integral) { _pitch_ctrl.reset_integrator(); } if (_att_sp.yaw_reset_integral) { _yaw_ctrl.reset_integrator(); } } else { /* * Scale down roll and pitch as the setpoints are radians * and a typical remote can only do around 45 degrees, the mapping is * -1..+1 to -man_roll_max rad..+man_roll_max rad (equivalent for pitch) * * With this mapping the stick angle is a 1:1 representation of * the commanded attitude. * * The trim gets subtracted here from the manual setpoint to get * the intended attitude setpoint. Later, after the rate control step the * trim is added again to the control signal. */ roll_sp = (_manual.y * _parameters.man_roll_max) + _parameters.rollsp_offset_rad; pitch_sp = -(_manual.x * _parameters.man_pitch_max) + _parameters.pitchsp_offset_rad; /* allow manual control of rudder deflection */ yaw_manual = _manual.r; throttle_sp = _manual.z; /* * in manual mode no external source should / does emit attitude setpoints. * emit the manual setpoint here to allow attitude controller tuning * in attitude control mode. */ struct vehicle_attitude_setpoint_s att_sp; att_sp.timestamp = hrt_absolute_time(); att_sp.roll_body = roll_sp; att_sp.pitch_body = pitch_sp; att_sp.yaw_body = 0.0f - _parameters.trim_yaw; att_sp.thrust = throttle_sp; /* lazily publish the setpoint only once available */ if (!_vehicle_status.is_rotary_wing) { if (_attitude_sp_pub != nullptr) { /* publish the attitude setpoint */ orb_publish(ORB_ID(vehicle_attitude_setpoint), _attitude_sp_pub, &att_sp); } else { /* advertise and publish */ _attitude_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &att_sp); } } } /* If the aircraft is on ground reset the integrators */ if (_vehicle_status.condition_landed || _vehicle_status.is_rotary_wing) { _roll_ctrl.reset_integrator(); _pitch_ctrl.reset_integrator(); _yaw_ctrl.reset_integrator(); } /* Prepare speed_body_u and speed_body_w */ float speed_body_u = 0.0f; float speed_body_v = 0.0f; float speed_body_w = 0.0f; if(_att.R_valid) { speed_body_u = PX4_R(_att.R, 0, 0) * _global_pos.vel_n + PX4_R(_att.R, 1, 0) * _global_pos.vel_e + PX4_R(_att.R, 2, 0) * _global_pos.vel_d; speed_body_v = PX4_R(_att.R, 0, 1) * _global_pos.vel_n + PX4_R(_att.R, 1, 1) * _global_pos.vel_e + PX4_R(_att.R, 2, 1) * _global_pos.vel_d; speed_body_w = PX4_R(_att.R, 0, 2) * _global_pos.vel_n + PX4_R(_att.R, 1, 2) * _global_pos.vel_e + PX4_R(_att.R, 2, 2) * _global_pos.vel_d; } else { if (_debug && loop_counter % 10 == 0) { warnx("Did not get a valid R\n"); } } /* Prepare data for attitude controllers */ struct ECL_ControlData control_input = {}; control_input.roll = _att.roll; control_input.pitch = _att.pitch; control_input.yaw = _att.yaw; control_input.roll_rate = _att.rollspeed; control_input.pitch_rate = _att.pitchspeed; control_input.yaw_rate = _att.yawspeed; control_input.speed_body_u = speed_body_u; control_input.speed_body_v = speed_body_v; control_input.speed_body_w = speed_body_w; control_input.acc_body_x = _accel.x; control_input.acc_body_y = _accel.y; control_input.acc_body_z = _accel.z; control_input.roll_setpoint = roll_sp; control_input.pitch_setpoint = pitch_sp; control_input.airspeed_min = _parameters.airspeed_min; control_input.airspeed_max = _parameters.airspeed_max; control_input.airspeed = airspeed; control_input.scaler = airspeed_scaling; control_input.lock_integrator = lock_integrator; /* Run attitude controllers */ if (isfinite(roll_sp) && isfinite(pitch_sp)) { _roll_ctrl.control_attitude(control_input); _pitch_ctrl.control_attitude(control_input); _yaw_ctrl.control_attitude(control_input); //runs last, because is depending on output of roll and pitch attitude /* Update input data for rate controllers */ control_input.roll_rate_setpoint = _roll_ctrl.get_desired_rate(); control_input.pitch_rate_setpoint = _pitch_ctrl.get_desired_rate(); control_input.yaw_rate_setpoint = _yaw_ctrl.get_desired_rate(); /* Run attitude RATE controllers which need the desired attitudes from above, add trim */ float roll_u = _roll_ctrl.control_bodyrate(control_input); _actuators.control[0] = (isfinite(roll_u)) ? roll_u + _parameters.trim_roll : _parameters.trim_roll; if (!isfinite(roll_u)) { _roll_ctrl.reset_integrator(); perf_count(_nonfinite_output_perf); if (_debug && loop_counter % 10 == 0) { warnx("roll_u %.4f", (double)roll_u); } } float pitch_u = _pitch_ctrl.control_bodyrate(control_input); _actuators.control[1] = (isfinite(pitch_u)) ? pitch_u + _parameters.trim_pitch : _parameters.trim_pitch; if (!isfinite(pitch_u)) { _pitch_ctrl.reset_integrator(); perf_count(_nonfinite_output_perf); if (_debug && loop_counter % 10 == 0) { warnx("pitch_u %.4f, _yaw_ctrl.get_desired_rate() %.4f," " airspeed %.4f, airspeed_scaling %.4f," " roll_sp %.4f, pitch_sp %.4f," " _roll_ctrl.get_desired_rate() %.4f," " _pitch_ctrl.get_desired_rate() %.4f" " att_sp.roll_body %.4f", (double)pitch_u, (double)_yaw_ctrl.get_desired_rate(), (double)airspeed, (double)airspeed_scaling, (double)roll_sp, (double)pitch_sp, (double)_roll_ctrl.get_desired_rate(), (double)_pitch_ctrl.get_desired_rate(), (double)_att_sp.roll_body); } } float yaw_u = _yaw_ctrl.control_bodyrate(control_input); _actuators.control[2] = (isfinite(yaw_u)) ? yaw_u + _parameters.trim_yaw : _parameters.trim_yaw; /* add in manual rudder control */ _actuators.control[2] += yaw_manual; if (!isfinite(yaw_u)) { _yaw_ctrl.reset_integrator(); perf_count(_nonfinite_output_perf); if (_debug && loop_counter % 10 == 0) { warnx("yaw_u %.4f", (double)yaw_u); } } /* throttle passed through if it is finite and if no engine failure was * detected */ _actuators.control[3] = (isfinite(throttle_sp) && !(_vehicle_status.engine_failure || _vehicle_status.engine_failure_cmd)) ? throttle_sp : 0.0f; if (!isfinite(throttle_sp)) { if (_debug && loop_counter % 10 == 0) { warnx("throttle_sp %.4f", (double)throttle_sp); } } } else { perf_count(_nonfinite_input_perf); if (_debug && loop_counter % 10 == 0) { warnx("Non-finite setpoint roll_sp: %.4f, pitch_sp %.4f", (double)roll_sp, (double)pitch_sp); } } /* * Lazily publish the rate setpoint (for analysis, the actuators are published below) * only once available */ _rates_sp.roll = _roll_ctrl.get_desired_rate(); _rates_sp.pitch = _pitch_ctrl.get_desired_rate(); _rates_sp.yaw = _yaw_ctrl.get_desired_rate(); _rates_sp.timestamp = hrt_absolute_time(); if (_rate_sp_pub != nullptr) { /* publish the attitude rates setpoint */ orb_publish(_rates_sp_id, _rate_sp_pub, &_rates_sp); } else if (_rates_sp_id) { /* advertise the attitude rates setpoint */ _rate_sp_pub = orb_advertise(_rates_sp_id, &_rates_sp); } } else { /* manual/direct control */ _actuators.control[actuator_controls_s::INDEX_ROLL] = _manual.y + _parameters.trim_roll; _actuators.control[actuator_controls_s::INDEX_PITCH] = -_manual.x + _parameters.trim_pitch; _actuators.control[actuator_controls_s::INDEX_YAW] = _manual.r + _parameters.trim_yaw; _actuators.control[actuator_controls_s::INDEX_THROTTLE] = _manual.z; } _actuators.control[actuator_controls_s::INDEX_FLAPS] = flaps_control; _actuators.control[5] = _manual.aux1; _actuators.control[6] = _manual.aux2; _actuators.control[7] = _manual.aux3; /* lazily publish the setpoint only once available */ _actuators.timestamp = hrt_absolute_time(); _actuators.timestamp_sample = _att.timestamp; _actuators_airframe.timestamp = hrt_absolute_time(); _actuators_airframe.timestamp_sample = _att.timestamp; /* Only publish if any of the proper modes are enabled */ if(_vcontrol_mode.flag_control_rates_enabled || _vcontrol_mode.flag_control_attitude_enabled || _vcontrol_mode.flag_control_manual_enabled) { /* publish the actuator controls */ if (_actuators_0_pub != nullptr) { orb_publish(_actuators_id, _actuators_0_pub, &_actuators); } else if (_actuators_id) { _actuators_0_pub= orb_advertise(_actuators_id, &_actuators); } if (_actuators_2_pub != nullptr) { /* publish the actuator controls*/ orb_publish(ORB_ID(actuator_controls_2), _actuators_2_pub, &_actuators_airframe); } else { /* advertise and publish */ _actuators_2_pub = orb_advertise(ORB_ID(actuator_controls_2), &_actuators_airframe); } } } loop_counter++; perf_end(_loop_perf); } warnx("exiting.\n"); _control_task = -1; _task_running = false; _exit(0); }
/******************************************************************************* * *nav_loop() * * Navigation control loop of the fixedwing controller * This loop calculates the roll,pitch and throttle setpoints, which are needed * to attain the desired heading, altitude and velocity. * * Input: none * * Output: none * ******************************************************************************/ static void *nav_loop(void *arg) { // Set thread name prctl(1, "fixedwing_control nav", getpid()); /* Set up to publish fixed wing control messages */ struct fixedwing_control_s control; int fixedwing_control_pub = orb_advertise(ORB_ID(fixedwing_control), &control); /* Subscribe to global position, attitude and rc */ struct vehicle_global_position_s global_pos; int global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position)); struct vehicle_attitude_s att; int attitude_sub = orb_subscribe(ORB_ID(vehicle_attitude)); struct rc_channels_s rc; int rc_sub = orb_subscribe(ORB_ID(rc_channels)); while (1) { /* get position, attitude and rc inputs */ // XXX add error checking orb_copy(ORB_ID(vehicle_global_position), global_pos_sub, &global_pos); orb_copy(ORB_ID(vehicle_attitude), attitude_sub, &attitude); orb_copy(ORB_ID(rc_channels), rc_sub, &rc); /* scaling factors are defined by the data from the APM Planner * TODO: ifdef for other parameters (HIL/Real world switch) */ plane_data.lat = global_pos.lat / 10000000; plane_data.lon = global_pos.lon / 10000000; plane_data.alt = global_pos.alt / 1000; plane_data.vx = global_pos.vx / 100; plane_data.vy = global_pos.vy / 100; plane_data.vz = global_pos.vz / 100; plane_data.roll = att.roll; plane_data.pitch = att.pitch; plane_data.yaw = att.yaw; plane_data.rollspeed = att.rollspeed; plane_data.pitchspeed = att.pitchspeed; plane_data.yawspeed = att.yawspeed; // Get GPS Waypoint // if(global_data_wait(&global_data_position_setpoint->access_conf) == 0) // { // plane_data.wp_x = global_data_position_setpoint->x; // plane_data.wp_y = global_data_position_setpoint->y; // plane_data.wp_z = global_data_position_setpoint->z; // } // global_data_unlock(&global_data_position_setpoint->access_conf); if (global_data_rc_channels->chan[global_data_rc_channels->function[OVERRIDE]].scale < MANUAL) { // AUTO mode // AUTO/HYBRID switch if (global_data_rc_channels->chan[global_data_rc_channels->function[OVERRIDE]].scale < AUTO) { plane_data.roll_setpoint = calc_roll_setpoint(); plane_data.pitch_setpoint = calc_pitch_setpoint(); plane_data.throttle_setpoint = calc_throttle_setpoint(); } else { plane_data.roll_setpoint = global_data_rc_channels->chan[global_data_rc_channels->function[ROLL]].scale / 200; plane_data.pitch_setpoint = global_data_rc_channels->chan[global_data_rc_channels->function[PITCH]].scale / 200; plane_data.throttle_setpoint = global_data_rc_channels->chan[global_data_rc_channels->function[THROTTLE]].scale / 200; } //control_outputs.yaw_rudder = calc_yaw_rudder(plane_data.hdg); // 10 Hz loop usleep(100000); } else { control->attitude_control_output[ROLL] = global_data_rc_channels->chan[global_data_rc_channels->function[ROLL]].scale; control->attitude_control_output[PITCH] = global_data_rc_channels->chan[global_data_rc_channels->function[PITCH]].scale; control->attitude_control_output[THROTTLE] = global_data_rc_channels->chan[global_data_rc_channels->function[THROTTLE]].scale; // since we don't have a yaw rudder //global_data_fixedwing_control->attitude_control_output[3] = global_data_rc_channels->chan[YAW].scale; control->counter++; control->timestamp = hrt_absolute_time(); #error Either publish here or above, not at two locations orb_publish(ORB_ID(fixedwing_control), fixedwing_control_pub, &control); usleep(100000); } } return NULL; }
void Ekf2::task_main() { // subscribe to relevant topics _sensors_sub = orb_subscribe(ORB_ID(sensor_combined)); _gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position)); _airspeed_sub = orb_subscribe(ORB_ID(airspeed)); _params_sub = orb_subscribe(ORB_ID(parameter_update)); _vehicle_status_sub = orb_subscribe(ORB_ID(vehicle_status)); _optical_flow_sub = orb_subscribe(ORB_ID(optical_flow)); _range_finder_sub = orb_subscribe(ORB_ID(distance_sensor)); px4_pollfd_struct_t fds[2] = {}; fds[0].fd = _sensors_sub; fds[0].events = POLLIN; fds[1].fd = _params_sub; fds[1].events = POLLIN; // initialise parameter cache updateParams(); // initialize data structures outside of loop // because they will else not always be // properly populated sensor_combined_s sensors = {}; vehicle_gps_position_s gps = {}; airspeed_s airspeed = {}; vehicle_control_mode_s vehicle_control_mode = {}; optical_flow_s optical_flow = {}; distance_sensor_s range_finder = {}; while (!_task_should_exit) { int ret = px4_poll(fds, sizeof(fds) / sizeof(fds[0]), 1000); if (ret < 0) { // Poll error, sleep and try again usleep(10000); continue; } else if (ret == 0) { // Poll timeout or no new data, do nothing continue; } if (fds[1].revents & POLLIN) { // read from param to clear updated flag struct parameter_update_s update; orb_copy(ORB_ID(parameter_update), _params_sub, &update); updateParams(); // fetch sensor data in next loop continue; } else if (!(fds[0].revents & POLLIN)) { // no new data continue; } bool gps_updated = false; bool airspeed_updated = false; bool vehicle_status_updated = false; bool optical_flow_updated = false; bool range_finder_updated = false; orb_copy(ORB_ID(sensor_combined), _sensors_sub, &sensors); // update all other topics if they have new data orb_check(_gps_sub, &gps_updated); if (gps_updated) { orb_copy(ORB_ID(vehicle_gps_position), _gps_sub, &gps); } orb_check(_airspeed_sub, &airspeed_updated); if (airspeed_updated) { orb_copy(ORB_ID(airspeed), _airspeed_sub, &airspeed); } orb_check(_optical_flow_sub, &optical_flow_updated); if (optical_flow_updated) { orb_copy(ORB_ID(optical_flow), _optical_flow_sub, &optical_flow); } orb_check(_range_finder_sub, &range_finder_updated); if (range_finder_updated) { orb_copy(ORB_ID(distance_sensor), _range_finder_sub, &range_finder); } // in replay mode we are getting the actual timestamp from the sensor topic hrt_abstime now = 0; if (_replay_mode) { now = sensors.timestamp; } else { now = hrt_absolute_time(); } // push imu data into estimator _ekf->setIMUData(now, sensors.gyro_integral_dt[0], sensors.accelerometer_integral_dt[0], &sensors.gyro_integral_rad[0], &sensors.accelerometer_integral_m_s[0]); // read mag data _ekf->setMagData(sensors.magnetometer_timestamp[0], &sensors.magnetometer_ga[0]); // read baro data _ekf->setBaroData(sensors.baro_timestamp[0], &sensors.baro_alt_meter[0]); // read gps data if available if (gps_updated) { struct gps_message gps_msg = {}; gps_msg.time_usec = gps.timestamp_position; gps_msg.lat = gps.lat; gps_msg.lon = gps.lon; gps_msg.alt = gps.alt; gps_msg.fix_type = gps.fix_type; gps_msg.eph = gps.eph; gps_msg.epv = gps.epv; gps_msg.sacc = gps.s_variance_m_s; gps_msg.time_usec_vel = gps.timestamp_velocity; gps_msg.vel_m_s = gps.vel_m_s; gps_msg.vel_ned[0] = gps.vel_n_m_s; gps_msg.vel_ned[1] = gps.vel_e_m_s; gps_msg.vel_ned[2] = gps.vel_d_m_s; gps_msg.vel_ned_valid = gps.vel_ned_valid; gps_msg.nsats = gps.satellites_used; //TODO add gdop to gps topic gps_msg.gdop = 0.0f; _ekf->setGpsData(gps.timestamp_position, &gps_msg); } // read airspeed data if available if (airspeed_updated) { _ekf->setAirspeedData(airspeed.timestamp, &airspeed.true_airspeed_m_s); // Only TAS is now fed into the estimator } if (optical_flow_updated) { flow_message flow; flow.flowdata(0) = optical_flow.pixel_flow_x_integral; flow.flowdata(1) = optical_flow.pixel_flow_y_integral; flow.quality = optical_flow.quality; flow.gyrodata(0) = optical_flow.gyro_x_rate_integral; flow.gyrodata(1) = optical_flow.gyro_y_rate_integral; flow.dt = optical_flow.integration_timespan; if (!isnan(optical_flow.pixel_flow_y_integral) && !isnan(optical_flow.pixel_flow_x_integral)) { _ekf->setOpticalFlowData(optical_flow.timestamp, &flow); } } if (range_finder_updated) { _ekf->setRangeData(range_finder.timestamp, &range_finder.current_distance); } // read vehicle status if available for 'landed' information orb_check(_vehicle_status_sub, &vehicle_status_updated); if (vehicle_status_updated) { struct vehicle_status_s status = {}; orb_copy(ORB_ID(vehicle_status), _vehicle_status_sub, &status); _ekf->set_in_air_status(!status.condition_landed); _ekf->set_arm_status(status.arming_state & vehicle_status_s::ARMING_STATE_ARMED); } // run the EKF update and output if (_ekf->update()) { // generate vehicle attitude quaternion data struct vehicle_attitude_s att = {}; _ekf->copy_quaternion(att.q); matrix::Quaternion<float> q(att.q[0], att.q[1], att.q[2], att.q[3]); // generate control state data control_state_s ctrl_state = {}; ctrl_state.timestamp = hrt_absolute_time(); ctrl_state.roll_rate = _lp_roll_rate.apply(sensors.gyro_rad_s[0]); ctrl_state.pitch_rate = _lp_pitch_rate.apply(sensors.gyro_rad_s[1]); ctrl_state.yaw_rate = _lp_yaw_rate.apply(sensors.gyro_rad_s[2]); ctrl_state.q[0] = q(0); ctrl_state.q[1] = q(1); ctrl_state.q[2] = q(2); ctrl_state.q[3] = q(3); // publish control state data if (_control_state_pub == nullptr) { _control_state_pub = orb_advertise(ORB_ID(control_state), &ctrl_state); } else { orb_publish(ORB_ID(control_state), _control_state_pub, &ctrl_state); } // generate remaining vehicle attitude data att.timestamp = hrt_absolute_time(); matrix::Euler<float> euler(q); att.roll = euler(0); att.pitch = euler(1); att.yaw = euler(2); att.q[0] = q(0); att.q[1] = q(1); att.q[2] = q(2); att.q[3] = q(3); att.q_valid = true; att.rollspeed = sensors.gyro_rad_s[0]; att.pitchspeed = sensors.gyro_rad_s[1]; att.yawspeed = sensors.gyro_rad_s[2]; // publish vehicle attitude data if (_att_pub == nullptr) { _att_pub = orb_advertise(ORB_ID(vehicle_attitude), &att); } else { orb_publish(ORB_ID(vehicle_attitude), _att_pub, &att); } // generate vehicle local position data struct vehicle_local_position_s lpos = {}; float pos[3] = {}; float vel[3] = {}; lpos.timestamp = hrt_absolute_time(); // Position in local NED frame _ekf->copy_position(pos); lpos.x = pos[0]; lpos.y = pos[1]; lpos.z = pos[2]; // Velocity in NED frame (m/s) _ekf->copy_velocity(vel); lpos.vx = vel[0]; lpos.vy = vel[1]; lpos.vz = vel[2]; // TODO: better status reporting lpos.xy_valid = _ekf->local_position_is_valid(); lpos.z_valid = true; lpos.v_xy_valid = _ekf->local_position_is_valid(); lpos.v_z_valid = true; // Position of local NED origin in GPS / WGS84 frame struct map_projection_reference_s ekf_origin = {}; // true if position (x, y) is valid and has valid global reference (ref_lat, ref_lon) _ekf->get_ekf_origin(&lpos.ref_timestamp, &ekf_origin, &lpos.ref_alt); lpos.xy_global = _ekf->global_position_is_valid(); lpos.z_global = true; // true if z is valid and has valid global reference (ref_alt) lpos.ref_lat = ekf_origin.lat_rad * 180.0 / M_PI; // Reference point latitude in degrees lpos.ref_lon = ekf_origin.lon_rad * 180.0 / M_PI; // Reference point longitude in degrees // The rotation of the tangent plane vs. geographical north lpos.yaw = att.yaw; float terrain_vpos; lpos.dist_bottom_valid = _ekf->get_terrain_vert_pos(&terrain_vpos); lpos.dist_bottom = terrain_vpos - pos[2]; // Distance to bottom surface (ground) in meters lpos.dist_bottom_rate = -vel[2]; // Distance to bottom surface (ground) change rate lpos.surface_bottom_timestamp = hrt_absolute_time(); // Time when new bottom surface found // TODO: uORB definition does not define what these variables are. We have assumed them to be horizontal and vertical 1-std dev accuracy in metres Vector3f pos_var, vel_var; _ekf->get_pos_var(pos_var); _ekf->get_vel_var(vel_var); lpos.eph = sqrt(pos_var(0) + pos_var(1)); lpos.epv = sqrt(pos_var(2)); // publish vehicle local position data if (_lpos_pub == nullptr) { _lpos_pub = orb_advertise(ORB_ID(vehicle_local_position), &lpos); } else { orb_publish(ORB_ID(vehicle_local_position), _lpos_pub, &lpos); } // generate and publish global position data struct vehicle_global_position_s global_pos = {}; if (_ekf->global_position_is_valid()) { global_pos.timestamp = hrt_absolute_time(); // Time of this estimate, in microseconds since system start global_pos.time_utc_usec = gps.time_utc_usec; // GPS UTC timestamp in microseconds double est_lat, est_lon; map_projection_reproject(&ekf_origin, lpos.x, lpos.y, &est_lat, &est_lon); global_pos.lat = est_lat; // Latitude in degrees global_pos.lon = est_lon; // Longitude in degrees global_pos.alt = -pos[2] + lpos.ref_alt; // Altitude AMSL in meters global_pos.vel_n = vel[0]; // Ground north velocity, m/s global_pos.vel_e = vel[1]; // Ground east velocity, m/s global_pos.vel_d = vel[2]; // Ground downside velocity, m/s global_pos.yaw = euler(2); // Yaw in radians -PI..+PI. global_pos.eph = sqrt(pos_var(0) + pos_var(1));; // Standard deviation of position estimate horizontally global_pos.epv = sqrt(pos_var(2)); // Standard deviation of position vertically // TODO: implement terrain estimator global_pos.terrain_alt = 0.0f; // Terrain altitude in m, WGS84 global_pos.terrain_alt_valid = false; // Terrain altitude estimate is valid // TODO use innovatun consistency check timouts to set this global_pos.dead_reckoning = false; // True if this position is estimated through dead-reckoning global_pos.pressure_alt = sensors.baro_alt_meter[0]; // Pressure altitude AMSL (m) if (_vehicle_global_position_pub == nullptr) { _vehicle_global_position_pub = orb_advertise(ORB_ID(vehicle_global_position), &global_pos); } else { orb_publish(ORB_ID(vehicle_global_position), _vehicle_global_position_pub, &global_pos); } } } // publish estimator status struct estimator_status_s status = {}; status.timestamp = hrt_absolute_time(); _ekf->get_state_delayed(status.states); _ekf->get_covariances(status.covariances); //status.gps_check_fail_flags = _ekf->_gps_check_fail_status.value; if (_estimator_status_pub == nullptr) { _estimator_status_pub = orb_advertise(ORB_ID(estimator_status), &status); } else { orb_publish(ORB_ID(estimator_status), _estimator_status_pub, &status); } // publish estimator innovation data struct ekf2_innovations_s innovations = {}; innovations.timestamp = hrt_absolute_time(); _ekf->get_vel_pos_innov(&innovations.vel_pos_innov[0]); _ekf->get_mag_innov(&innovations.mag_innov[0]); _ekf->get_heading_innov(&innovations.heading_innov); _ekf->get_airspeed_innov(&innovations.airspeed_innov); _ekf->get_flow_innov(&innovations.flow_innov[0]); _ekf->get_hagl_innov(&innovations.hagl_innov); _ekf->get_vel_pos_innov_var(&innovations.vel_pos_innov_var[0]); _ekf->get_mag_innov_var(&innovations.mag_innov_var[0]); _ekf->get_heading_innov_var(&innovations.heading_innov_var); _ekf->get_airspeed_innov_var(&innovations.airspeed_innov_var); _ekf->get_flow_innov_var(&innovations.flow_innov_var[0]); _ekf->get_hagl_innov_var(&innovations.hagl_innov_var); if (_estimator_innovations_pub == nullptr) { _estimator_innovations_pub = orb_advertise(ORB_ID(ekf2_innovations), &innovations); } else { orb_publish(ORB_ID(ekf2_innovations), _estimator_innovations_pub, &innovations); } // save the declination to the EKF2_MAG_DECL parameter when a dis-arm event is detected if ((_params->mag_declination_source & (1 << 1)) && _prev_motors_armed && !vehicle_control_mode.flag_armed) { float decl_deg; _ekf->copy_mag_decl_deg(&decl_deg); _mag_declination_deg->set(decl_deg); } // publish replay message if in replay mode bool publish_replay_message = (bool)_param_record_replay_msg->get(); if (publish_replay_message) { struct ekf2_replay_s replay = {}; replay.time_ref = now; replay.gyro_integral_dt = sensors.gyro_integral_dt[0]; replay.accelerometer_integral_dt = sensors.accelerometer_integral_dt[0]; replay.magnetometer_timestamp = sensors.magnetometer_timestamp[0]; replay.baro_timestamp = sensors.baro_timestamp[0]; memcpy(&replay.gyro_integral_rad[0], &sensors.gyro_integral_rad[0], sizeof(replay.gyro_integral_rad)); memcpy(&replay.accelerometer_integral_m_s[0], &sensors.accelerometer_integral_m_s[0], sizeof(replay.accelerometer_integral_m_s)); memcpy(&replay.magnetometer_ga[0], &sensors.magnetometer_ga[0], sizeof(replay.magnetometer_ga)); replay.baro_alt_meter = sensors.baro_alt_meter[0]; // only write gps data if we had a gps update. if (gps_updated) { replay.time_usec = gps.timestamp_position; replay.time_usec_vel = gps.timestamp_velocity; replay.lat = gps.lat; replay.lon = gps.lon; replay.alt = gps.alt; replay.fix_type = gps.fix_type; replay.nsats = gps.satellites_used; replay.eph = gps.eph; replay.epv = gps.epv; replay.sacc = gps.s_variance_m_s; replay.vel_m_s = gps.vel_m_s; replay.vel_n_m_s = gps.vel_n_m_s; replay.vel_e_m_s = gps.vel_e_m_s; replay.vel_d_m_s = gps.vel_d_m_s; replay.vel_ned_valid = gps.vel_ned_valid; } else { // this will tell the logging app not to bother logging any gps replay data replay.time_usec = 0; } if (optical_flow_updated) { replay.flow_timestamp = optical_flow.timestamp; replay.flow_pixel_integral[0] = optical_flow.pixel_flow_x_integral; replay.flow_pixel_integral[1] = optical_flow.pixel_flow_y_integral; replay.flow_gyro_integral[0] = optical_flow.gyro_x_rate_integral; replay.flow_gyro_integral[1] = optical_flow.gyro_y_rate_integral; replay.flow_time_integral = optical_flow.integration_timespan; replay.flow_quality = optical_flow.quality; } else { replay.flow_timestamp = 0; } if (range_finder_updated) { replay.rng_timestamp = range_finder.timestamp; replay.range_to_ground = range_finder.current_distance; } else { replay.rng_timestamp = 0; } if (_replay_pub == nullptr) { _replay_pub = orb_advertise(ORB_ID(ekf2_replay), &replay); } else { orb_publish(ORB_ID(ekf2_replay), _replay_pub, &replay); } } } delete ekf2::instance; ekf2::instance = nullptr; }
void MulticopterAttitudeControl::task_main() { /* * do subscriptions */ _v_att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint)); _v_rates_sp_sub = orb_subscribe(ORB_ID(vehicle_rates_setpoint)); _v_att_sub = orb_subscribe(ORB_ID(vehicle_attitude)); _v_control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode)); _params_sub = orb_subscribe(ORB_ID(parameter_update)); _manual_control_sp_sub = orb_subscribe(ORB_ID(manual_control_setpoint)); _armed_sub = orb_subscribe(ORB_ID(actuator_armed)); _vehicle_status_sub = orb_subscribe(ORB_ID(vehicle_status)); _motor_limits_sub = orb_subscribe(ORB_ID(multirotor_motor_limits)); /* initialize parameters cache */ parameters_update(); /* wakeup source: vehicle attitude */ struct pollfd fds[1]; fds[0].fd = _v_att_sub; fds[0].events = POLLIN; while (!_task_should_exit) { /* wait for up to 100ms for data */ int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100); /* timed out - periodic check for _task_should_exit */ if (pret == 0) continue; /* this is undesirable but not much we can do - might want to flag unhappy status */ if (pret < 0) { warn("poll error %d, %d", pret, errno); /* sleep a bit before next try */ usleep(100000); continue; } perf_begin(_loop_perf); /* run controller on attitude changes */ if (fds[0].revents & POLLIN) { static uint64_t last_run = 0; float dt = (hrt_absolute_time() - last_run) / 1000000.0f; last_run = hrt_absolute_time(); /* guard against too small (< 2ms) and too large (> 20ms) dt's */ if (dt < 0.002f) { dt = 0.002f; } else if (dt > 0.02f) { dt = 0.02f; } /* copy attitude topic */ orb_copy(ORB_ID(vehicle_attitude), _v_att_sub, &_v_att); /* check for updates in other topics */ parameter_update_poll(); vehicle_control_mode_poll(); arming_status_poll(); vehicle_manual_poll(); vehicle_status_poll(); vehicle_motor_limits_poll(); if (_v_control_mode.flag_control_attitude_enabled) { control_attitude(dt); /* publish attitude rates setpoint */ _v_rates_sp.roll = _rates_sp(0); _v_rates_sp.pitch = _rates_sp(1); _v_rates_sp.yaw = _rates_sp(2); _v_rates_sp.thrust = _thrust_sp; _v_rates_sp.timestamp = hrt_absolute_time(); if (_v_rates_sp_pub > 0) { orb_publish(_rates_sp_id, _v_rates_sp_pub, &_v_rates_sp); } else if (_rates_sp_id) { _v_rates_sp_pub = orb_advertise(_rates_sp_id, &_v_rates_sp); } } else { /* attitude controller disabled, poll rates setpoint topic */ if (_v_control_mode.flag_control_manual_enabled) { /* manual rates control - ACRO mode */ _rates_sp = math::Vector<3>(_manual_control_sp.y, -_manual_control_sp.x, _manual_control_sp.r).emult(_params.acro_rate_max); _thrust_sp = math::min(_manual_control_sp.z, MANUAL_THROTTLE_MAX_MULTICOPTER); /* publish attitude rates setpoint */ _v_rates_sp.roll = _rates_sp(0); _v_rates_sp.pitch = _rates_sp(1); _v_rates_sp.yaw = _rates_sp(2); _v_rates_sp.thrust = _thrust_sp; _v_rates_sp.timestamp = hrt_absolute_time(); if (_v_rates_sp_pub > 0) { orb_publish(_rates_sp_id, _v_rates_sp_pub, &_v_rates_sp); } else if (_rates_sp_id) { _v_rates_sp_pub = orb_advertise(_rates_sp_id, &_v_rates_sp); } } else { /* attitude controller disabled, poll rates setpoint topic */ vehicle_rates_setpoint_poll(); _rates_sp(0) = _v_rates_sp.roll; _rates_sp(1) = _v_rates_sp.pitch; _rates_sp(2) = _v_rates_sp.yaw; _thrust_sp = _v_rates_sp.thrust; } } if (_v_control_mode.flag_control_rates_enabled) { control_attitude_rates(dt); /* publish actuator controls */ _actuators.control[0] = (isfinite(_att_control(0))) ? _att_control(0) : 0.0f; _actuators.control[1] = (isfinite(_att_control(1))) ? _att_control(1) : 0.0f; _actuators.control[2] = (isfinite(_att_control(2))) ? _att_control(2) : 0.0f; _actuators.control[3] = (isfinite(_thrust_sp)) ? _thrust_sp : 0.0f; _actuators.timestamp = hrt_absolute_time(); _actuators.timestamp_sample = _v_att.timestamp; _controller_status.roll_rate_integ = _rates_int(0); _controller_status.pitch_rate_integ = _rates_int(1); _controller_status.yaw_rate_integ = _rates_int(2); _controller_status.timestamp = hrt_absolute_time(); if (!_actuators_0_circuit_breaker_enabled) { if (_actuators_0_pub > 0) { orb_publish(_actuators_id, _actuators_0_pub, &_actuators); perf_end(_controller_latency_perf); } else if (_actuators_id) { _actuators_0_pub = orb_advertise(_actuators_id, &_actuators); } } /* publish controller status */ if(_controller_status_pub > 0) { orb_publish(ORB_ID(mc_att_ctrl_status),_controller_status_pub, &_controller_status); } else { _controller_status_pub = orb_advertise(ORB_ID(mc_att_ctrl_status), &_controller_status); } } } perf_end(_loop_perf); } warnx("exit"); _control_task = -1; _exit(0); }
void FixedwingEstimator::task_main() { _mavlink_fd = open(MAVLINK_LOG_DEVICE, 0); _ekf = new AttPosEKF(); float dt = 0.0f; // time lapsed since last covariance prediction _filter_start_time = hrt_absolute_time(); if (!_ekf) { errx(1, "OUT OF MEM!"); } /* * do subscriptions */ _baro_sub = orb_subscribe(ORB_ID(sensor_baro)); _airspeed_sub = orb_subscribe(ORB_ID(airspeed)); _gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position)); _vstatus_sub = orb_subscribe(ORB_ID(vehicle_status)); _params_sub = orb_subscribe(ORB_ID(parameter_update)); _home_sub = orb_subscribe(ORB_ID(home_position)); /* rate limit vehicle status updates to 5Hz */ orb_set_interval(_vstatus_sub, 200); #ifndef SENSOR_COMBINED_SUB _gyro_sub = orb_subscribe(ORB_ID(sensor_gyro)); _accel_sub = orb_subscribe(ORB_ID(sensor_accel)); _mag_sub = orb_subscribe(ORB_ID(sensor_mag)); /* rate limit gyro updates to 50 Hz */ /* XXX remove this!, BUT increase the data buffer size! */ orb_set_interval(_gyro_sub, 4); #else _sensor_combined_sub = orb_subscribe(ORB_ID(sensor_combined)); /* XXX remove this!, BUT increase the data buffer size! */ orb_set_interval(_sensor_combined_sub, 9); #endif /* sets also parameters in the EKF object */ parameters_update(); Vector3f lastAngRate; Vector3f lastAccel; /* wakeup source(s) */ struct pollfd fds[2]; /* Setup of loop */ fds[0].fd = _params_sub; fds[0].events = POLLIN; #ifndef SENSOR_COMBINED_SUB fds[1].fd = _gyro_sub; fds[1].events = POLLIN; #else fds[1].fd = _sensor_combined_sub; fds[1].events = POLLIN; #endif bool newDataGps = false; bool newHgtData = false; bool newAdsData = false; bool newDataMag = false; float posNED[3] = {0.0f, 0.0f, 0.0f}; // North, East Down position (m) uint64_t last_gps = 0; _gps.vel_n_m_s = 0.0f; _gps.vel_e_m_s = 0.0f; _gps.vel_d_m_s = 0.0f; while (!_task_should_exit) { /* wait for up to 500ms for data */ int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100); /* timed out - periodic check for _task_should_exit, etc. */ if (pret == 0) continue; /* this is undesirable but not much we can do - might want to flag unhappy status */ if (pret < 0) { warn("POLL ERR %d, %d", pret, errno); continue; } perf_begin(_loop_perf); /* only update parameters if they changed */ if (fds[0].revents & POLLIN) { /* read from param to clear updated flag */ struct parameter_update_s update; orb_copy(ORB_ID(parameter_update), _params_sub, &update); /* update parameters from storage */ parameters_update(); } /* only run estimator if gyro updated */ if (fds[1].revents & POLLIN) { /* check vehicle status for changes to publication state */ bool prev_hil = (_vstatus.hil_state == HIL_STATE_ON); vehicle_status_poll(); bool accel_updated; bool mag_updated; perf_count(_perf_gyro); /* Reset baro reference if switching to HIL, reset sensor states */ if (!prev_hil && (_vstatus.hil_state == HIL_STATE_ON)) { /* system is in HIL now, wait for measurements to come in one last round */ usleep(60000); #ifndef SENSOR_COMBINED_SUB orb_copy(ORB_ID(sensor_gyro), _gyro_sub, &_gyro); orb_copy(ORB_ID(sensor_accel), _accel_sub, &_accel); orb_copy(ORB_ID(sensor_mag), _mag_sub, &_mag); #else /* now read all sensor publications to ensure all real sensor data is purged */ orb_copy(ORB_ID(sensor_combined), _sensor_combined_sub, &_sensor_combined); #endif /* set sensors to de-initialized state */ _gyro_valid = false; _accel_valid = false; _mag_valid = false; _baro_init = false; _gps_initialized = false; _last_sensor_timestamp = hrt_absolute_time(); _last_run = _last_sensor_timestamp; _ekf->ZeroVariables(); _ekf->dtIMU = 0.01f; _filter_start_time = _last_sensor_timestamp; /* now skip this loop and get data on the next one, which will also re-init the filter */ continue; } /** * PART ONE: COLLECT ALL DATA **/ /* load local copies */ #ifndef SENSOR_COMBINED_SUB orb_copy(ORB_ID(sensor_gyro), _gyro_sub, &_gyro); orb_check(_accel_sub, &accel_updated); if (accel_updated) { orb_copy(ORB_ID(sensor_accel), _accel_sub, &_accel); } _last_sensor_timestamp = _gyro.timestamp; IMUmsec = _gyro.timestamp / 1e3f; float deltaT = (_gyro.timestamp - _last_run) / 1e6f; _last_run = _gyro.timestamp; /* guard against too large deltaT's */ if (!isfinite(deltaT) || deltaT > 1.0f || deltaT < 0.000001f) { deltaT = 0.01f; } // Always store data, independent of init status /* fill in last data set */ _ekf->dtIMU = deltaT; if (isfinite(_gyro.x) && isfinite(_gyro.y) && isfinite(_gyro.z)) { _ekf->angRate.x = _gyro.x; _ekf->angRate.y = _gyro.y; _ekf->angRate.z = _gyro.z; if (!_gyro_valid) { lastAngRate = _ekf->angRate; } _gyro_valid = true; } if (accel_updated) { _ekf->accel.x = _accel.x; _ekf->accel.y = _accel.y; _ekf->accel.z = _accel.z; if (!_accel_valid) { lastAccel = _ekf->accel; } _accel_valid = true; } _ekf->dAngIMU = 0.5f * (angRate + lastAngRate) * dtIMU; _ekf->lastAngRate = angRate; _ekf->dVelIMU = 0.5f * (accel + lastAccel) * dtIMU; _ekf->lastAccel = accel; #else orb_copy(ORB_ID(sensor_combined), _sensor_combined_sub, &_sensor_combined); static hrt_abstime last_accel = 0; static hrt_abstime last_mag = 0; if (last_accel != _sensor_combined.accelerometer_timestamp) { accel_updated = true; } else { accel_updated = false; } last_accel = _sensor_combined.accelerometer_timestamp; // Copy gyro and accel _last_sensor_timestamp = _sensor_combined.timestamp; IMUmsec = _sensor_combined.timestamp / 1e3f; float deltaT = (_sensor_combined.timestamp - _last_run) / 1e6f; /* guard against too large deltaT's */ if (!isfinite(deltaT) || deltaT > 1.0f || deltaT < 0.000001f) { deltaT = 0.01f; } _last_run = _sensor_combined.timestamp; // Always store data, independent of init status /* fill in last data set */ _ekf->dtIMU = deltaT; if (isfinite(_sensor_combined.gyro_rad_s[0]) && isfinite(_sensor_combined.gyro_rad_s[1]) && isfinite(_sensor_combined.gyro_rad_s[2])) { _ekf->angRate.x = _sensor_combined.gyro_rad_s[0]; _ekf->angRate.y = _sensor_combined.gyro_rad_s[1]; _ekf->angRate.z = _sensor_combined.gyro_rad_s[2]; if (!_gyro_valid) { lastAngRate = _ekf->angRate; } _gyro_valid = true; perf_count(_perf_gyro); } if (accel_updated) { _ekf->accel.x = _sensor_combined.accelerometer_m_s2[0]; _ekf->accel.y = _sensor_combined.accelerometer_m_s2[1]; _ekf->accel.z = _sensor_combined.accelerometer_m_s2[2]; if (!_accel_valid) { lastAccel = _ekf->accel; } _accel_valid = true; } _ekf->dAngIMU = 0.5f * (_ekf->angRate + lastAngRate) * _ekf->dtIMU; lastAngRate = _ekf->angRate; _ekf->dVelIMU = 0.5f * (_ekf->accel + lastAccel) * _ekf->dtIMU; lastAccel = _ekf->accel; if (last_mag != _sensor_combined.magnetometer_timestamp) { mag_updated = true; newDataMag = true; } else { newDataMag = false; } last_mag = _sensor_combined.magnetometer_timestamp; #endif //warnx("dang: %8.4f %8.4f dvel: %8.4f %8.4f", _ekf->dAngIMU.x, _ekf->dAngIMU.z, _ekf->dVelIMU.x, _ekf->dVelIMU.z); bool airspeed_updated; orb_check(_airspeed_sub, &airspeed_updated); if (airspeed_updated) { orb_copy(ORB_ID(airspeed), _airspeed_sub, &_airspeed); perf_count(_perf_airspeed); _ekf->VtasMeas = _airspeed.true_airspeed_m_s; newAdsData = true; } else { newAdsData = false; } bool gps_updated; orb_check(_gps_sub, &gps_updated); if (gps_updated) { last_gps = _gps.timestamp_position; orb_copy(ORB_ID(vehicle_gps_position), _gps_sub, &_gps); perf_count(_perf_gps); if (_gps.fix_type < 3) { newDataGps = false; } else { /* store time of valid GPS measurement */ _gps_start_time = hrt_absolute_time(); /* check if we had a GPS outage for a long time */ if (hrt_elapsed_time(&last_gps) > 5 * 1000 * 1000) { _ekf->ResetPosition(); _ekf->ResetVelocity(); _ekf->ResetStoredStates(); } /* fuse GPS updates */ //_gps.timestamp / 1e3; _ekf->GPSstatus = _gps.fix_type; _ekf->velNED[0] = _gps.vel_n_m_s; _ekf->velNED[1] = _gps.vel_e_m_s; _ekf->velNED[2] = _gps.vel_d_m_s; // warnx("GPS updated: status: %d, vel: %8.4f %8.4f %8.4f", (int)GPSstatus, velNED[0], velNED[1], velNED[2]); _ekf->gpsLat = math::radians(_gps.lat / (double)1e7); _ekf->gpsLon = math::radians(_gps.lon / (double)1e7) - M_PI; _ekf->gpsHgt = _gps.alt / 1e3f; // if (_gps.s_variance_m_s > 0.25f && _gps.s_variance_m_s < 100.0f * 100.0f) { // _ekf->vneSigma = sqrtf(_gps.s_variance_m_s); // } else { // _ekf->vneSigma = _parameters.velne_noise; // } // if (_gps.p_variance_m > 0.25f && _gps.p_variance_m < 100.0f * 100.0f) { // _ekf->posNeSigma = sqrtf(_gps.p_variance_m); // } else { // _ekf->posNeSigma = _parameters.posne_noise; // } // warnx("vel: %8.4f pos: %8.4f", _gps.s_variance_m_s, _gps.p_variance_m); newDataGps = true; } } bool baro_updated; orb_check(_baro_sub, &baro_updated); if (baro_updated) { orb_copy(ORB_ID(sensor_baro), _baro_sub, &_baro); _ekf->baroHgt = _baro.altitude; if (!_baro_init) { _baro_ref = _baro.altitude; _baro_init = true; warnx("ALT REF INIT"); } perf_count(_perf_baro); newHgtData = true; } else { newHgtData = false; } #ifndef SENSOR_COMBINED_SUB orb_check(_mag_sub, &mag_updated); #endif if (mag_updated) { _mag_valid = true; perf_count(_perf_mag); #ifndef SENSOR_COMBINED_SUB orb_copy(ORB_ID(sensor_mag), _mag_sub, &_mag); // XXX we compensate the offsets upfront - should be close to zero. // 0.001f _ekf->magData.x = _mag.x; _ekf->magBias.x = 0.000001f; // _mag_offsets.x_offset _ekf->magData.y = _mag.y; _ekf->magBias.y = 0.000001f; // _mag_offsets.y_offset _ekf->magData.z = _mag.z; _ekf->magBias.z = 0.000001f; // _mag_offsets.y_offset #else // XXX we compensate the offsets upfront - should be close to zero. // 0.001f _ekf->magData.x = _sensor_combined.magnetometer_ga[0]; _ekf->magBias.x = 0.000001f; // _mag_offsets.x_offset _ekf->magData.y = _sensor_combined.magnetometer_ga[1]; _ekf->magBias.y = 0.000001f; // _mag_offsets.y_offset _ekf->magData.z = _sensor_combined.magnetometer_ga[2]; _ekf->magBias.z = 0.000001f; // _mag_offsets.y_offset #endif newDataMag = true; } else { newDataMag = false; } /* * CHECK IF ITS THE RIGHT TIME TO RUN THINGS ALREADY */ if (hrt_elapsed_time(&_filter_start_time) < FILTER_INIT_DELAY) { continue; } /** * PART TWO: EXECUTE THE FILTER * * We run the filter only once all data has been fetched **/ if (_baro_init && _gyro_valid && _accel_valid && _mag_valid) { float initVelNED[3]; /* Initialize the filter first */ if (!_gps_initialized && _gps.fix_type > 2 && _gps.eph < _parameters.pos_stddev_threshold && _gps.epv < _parameters.pos_stddev_threshold) { // GPS is in scaled integers, convert double lat = _gps.lat / 1.0e7; double lon = _gps.lon / 1.0e7; float gps_alt = _gps.alt / 1e3f; initVelNED[0] = _gps.vel_n_m_s; initVelNED[1] = _gps.vel_e_m_s; initVelNED[2] = _gps.vel_d_m_s; // Set up height correctly orb_copy(ORB_ID(sensor_baro), _baro_sub, &_baro); _baro_ref_offset = _ekf->states[9]; // this should become zero in the local frame _baro_gps_offset = _baro.altitude - gps_alt; _ekf->baroHgt = _baro.altitude; _ekf->hgtMea = 1.0f * (_ekf->baroHgt - (_baro_ref)); // Set up position variables correctly _ekf->GPSstatus = _gps.fix_type; _ekf->gpsLat = math::radians(lat); _ekf->gpsLon = math::radians(lon) - M_PI; _ekf->gpsHgt = gps_alt; // Look up mag declination based on current position float declination = math::radians(get_mag_declination(lat, lon)); _ekf->InitialiseFilter(initVelNED, math::radians(lat), math::radians(lon) - M_PI, gps_alt, declination); // Initialize projection _local_pos.ref_lat = lat; _local_pos.ref_lon = lon; _local_pos.ref_alt = gps_alt; _local_pos.ref_timestamp = _gps.timestamp_position; map_projection_init(&_pos_ref, lat, lon); mavlink_log_info(_mavlink_fd, "[ekf] ref: LA %.4f,LO %.4f,ALT %.2f", lat, lon, (double)gps_alt); #if 0 warnx("HOME/REF: LA %8.4f,LO %8.4f,ALT %8.2f V: %8.4f %8.4f %8.4f", lat, lon, (double)gps_alt, (double)_ekf->velNED[0], (double)_ekf->velNED[1], (double)_ekf->velNED[2]); warnx("BARO: %8.4f m / ref: %8.4f m / gps offs: %8.4f m", (double)_ekf->baroHgt, (double)_baro_ref, (double)_baro_ref_offset); warnx("GPS: eph: %8.4f, epv: %8.4f, declination: %8.4f", (double)_gps.eph, (double)_gps.epv, (double)math::degrees(declination)); #endif _gps_initialized = true; } else if (!_ekf->statesInitialised) { initVelNED[0] = 0.0f; initVelNED[1] = 0.0f; initVelNED[2] = 0.0f; _ekf->posNE[0] = posNED[0]; _ekf->posNE[1] = posNED[1]; _local_pos.ref_alt = _baro_ref; _baro_ref_offset = 0.0f; _baro_gps_offset = 0.0f; _ekf->InitialiseFilter(initVelNED, 0.0, 0.0, 0.0f, 0.0f); } else if (_ekf->statesInitialised) { // We're apparently initialized in this case now int check = check_filter_state(); if (check) { // Let the system re-initialize itself continue; } // Run the strapdown INS equations every IMU update _ekf->UpdateStrapdownEquationsNED(); #if 0 // debug code - could be tunred into a filter mnitoring/watchdog function float tempQuat[4]; for (uint8_t j = 0; j <= 3; j++) tempQuat[j] = states[j]; quat2eul(eulerEst, tempQuat); for (uint8_t j = 0; j <= 2; j++) eulerDif[j] = eulerEst[j] - ahrsEul[j]; if (eulerDif[2] > pi) eulerDif[2] -= 2 * pi; if (eulerDif[2] < -pi) eulerDif[2] += 2 * pi; #endif // store the predicted states for subsequent use by measurement fusion _ekf->StoreStates(IMUmsec); // Check if on ground - status is used by covariance prediction _ekf->OnGroundCheck(); // sum delta angles and time used by covariance prediction _ekf->summedDelAng = _ekf->summedDelAng + _ekf->correctedDelAng; _ekf->summedDelVel = _ekf->summedDelVel + _ekf->dVelIMU; dt += _ekf->dtIMU; // perform a covariance prediction if the total delta angle has exceeded the limit // or the time limit will be exceeded at the next IMU update if ((dt >= (_ekf->covTimeStepMax - _ekf->dtIMU)) || (_ekf->summedDelAng.length() > _ekf->covDelAngMax)) { _ekf->CovariancePrediction(dt); _ekf->summedDelAng.zero(); _ekf->summedDelVel.zero(); dt = 0.0f; } // Fuse GPS Measurements if (newDataGps && _gps_initialized) { // Convert GPS measurements to Pos NE, hgt and Vel NED float gps_dt = (_gps.timestamp_position - last_gps) / 1e6f; // Calculate acceleration predicted by GPS velocity change if (((fabsf(_ekf->velNED[0] - _gps.vel_n_m_s) > FLT_EPSILON) || (fabsf(_ekf->velNED[1] - _gps.vel_e_m_s) > FLT_EPSILON) || (fabsf(_ekf->velNED[2] - _gps.vel_d_m_s) > FLT_EPSILON)) && (gps_dt > 0.00001f)) { _ekf->accelGPSNED[0] = (_ekf->velNED[0] - _gps.vel_n_m_s) / gps_dt; _ekf->accelGPSNED[1] = (_ekf->velNED[1] - _gps.vel_e_m_s) / gps_dt; _ekf->accelGPSNED[2] = (_ekf->velNED[2] - _gps.vel_d_m_s) / gps_dt; } _ekf->velNED[0] = _gps.vel_n_m_s; _ekf->velNED[1] = _gps.vel_e_m_s; _ekf->velNED[2] = _gps.vel_d_m_s; _ekf->calcposNED(posNED, _ekf->gpsLat, _ekf->gpsLon, _ekf->gpsHgt, _ekf->latRef, _ekf->lonRef, _ekf->hgtRef); _ekf->posNE[0] = posNED[0]; _ekf->posNE[1] = posNED[1]; // set fusion flags _ekf->fuseVelData = true; _ekf->fusePosData = true; // recall states stored at time of measurement after adjusting for delays _ekf->RecallStates(_ekf->statesAtVelTime, (IMUmsec - _parameters.vel_delay_ms)); _ekf->RecallStates(_ekf->statesAtPosTime, (IMUmsec - _parameters.pos_delay_ms)); // run the fusion step _ekf->FuseVelposNED(); } else if (_ekf->statesInitialised) { // Convert GPS measurements to Pos NE, hgt and Vel NED _ekf->velNED[0] = 0.0f; _ekf->velNED[1] = 0.0f; _ekf->velNED[2] = 0.0f; _ekf->posNE[0] = 0.0f; _ekf->posNE[1] = 0.0f; // set fusion flags _ekf->fuseVelData = true; _ekf->fusePosData = true; // recall states stored at time of measurement after adjusting for delays _ekf->RecallStates(_ekf->statesAtVelTime, (IMUmsec - _parameters.vel_delay_ms)); _ekf->RecallStates(_ekf->statesAtPosTime, (IMUmsec - _parameters.pos_delay_ms)); // run the fusion step _ekf->FuseVelposNED(); } else { _ekf->fuseVelData = false; _ekf->fusePosData = false; } if (newHgtData && _ekf->statesInitialised) { // Could use a blend of GPS and baro alt data if desired _ekf->hgtMea = 1.0f * (_ekf->baroHgt - _baro_ref); _ekf->fuseHgtData = true; // recall states stored at time of measurement after adjusting for delays _ekf->RecallStates(_ekf->statesAtHgtTime, (IMUmsec - _parameters.height_delay_ms)); // run the fusion step _ekf->FuseVelposNED(); } else { _ekf->fuseHgtData = false; } // Fuse Magnetometer Measurements if (newDataMag && _ekf->statesInitialised) { _ekf->fuseMagData = true; _ekf->RecallStates(_ekf->statesAtMagMeasTime, (IMUmsec - _parameters.mag_delay_ms)); // Assume 50 msec avg delay for magnetometer data _ekf->magstate.obsIndex = 0; _ekf->FuseMagnetometer(); _ekf->FuseMagnetometer(); _ekf->FuseMagnetometer(); } else { _ekf->fuseMagData = false; } // Fuse Airspeed Measurements if (newAdsData && _ekf->statesInitialised && _ekf->VtasMeas > 8.0f) { _ekf->fuseVtasData = true; _ekf->RecallStates(_ekf->statesAtVtasMeasTime, (IMUmsec - _parameters.tas_delay_ms)); // assume 100 msec avg delay for airspeed data _ekf->FuseAirspeed(); } else { _ekf->fuseVtasData = false; } // Output results math::Quaternion q(_ekf->states[0], _ekf->states[1], _ekf->states[2], _ekf->states[3]); math::Matrix<3, 3> R = q.to_dcm(); math::Vector<3> euler = R.to_euler(); for (int i = 0; i < 3; i++) for (int j = 0; j < 3; j++) _att.R[i][j] = R(i, j); _att.timestamp = _last_sensor_timestamp; _att.q[0] = _ekf->states[0]; _att.q[1] = _ekf->states[1]; _att.q[2] = _ekf->states[2]; _att.q[3] = _ekf->states[3]; _att.q_valid = true; _att.R_valid = true; _att.timestamp = _last_sensor_timestamp; _att.roll = euler(0); _att.pitch = euler(1); _att.yaw = euler(2); _att.rollspeed = _ekf->angRate.x - _ekf->states[10]; _att.pitchspeed = _ekf->angRate.y - _ekf->states[11]; _att.yawspeed = _ekf->angRate.z - _ekf->states[12]; // gyro offsets _att.rate_offsets[0] = _ekf->states[10]; _att.rate_offsets[1] = _ekf->states[11]; _att.rate_offsets[2] = _ekf->states[12]; /* lazily publish the attitude only once available */ if (_att_pub > 0) { /* publish the attitude setpoint */ orb_publish(ORB_ID(vehicle_attitude), _att_pub, &_att); } else { /* advertise and publish */ _att_pub = orb_advertise(ORB_ID(vehicle_attitude), &_att); } if (_gps_initialized) { _local_pos.timestamp = _last_sensor_timestamp; _local_pos.x = _ekf->states[7]; _local_pos.y = _ekf->states[8]; // XXX need to announce change of Z reference somehow elegantly _local_pos.z = _ekf->states[9] - _baro_ref_offset; _local_pos.vx = _ekf->states[4]; _local_pos.vy = _ekf->states[5]; _local_pos.vz = _ekf->states[6]; _local_pos.xy_valid = _gps_initialized; _local_pos.z_valid = true; _local_pos.v_xy_valid = _gps_initialized; _local_pos.v_z_valid = true; _local_pos.xy_global = true; _velocity_xy_filtered = 0.95f*_velocity_xy_filtered + 0.05f*sqrtf(_local_pos.vx*_local_pos.vx + _local_pos.vy*_local_pos.vy); _velocity_z_filtered = 0.95f*_velocity_z_filtered + 0.05f*fabsf(_local_pos.vz); _airspeed_filtered = 0.95f*_airspeed_filtered + + 0.05f*_airspeed.true_airspeed_m_s; /* crude land detector for fixedwing only, * TODO: adapt so that it works for both, maybe move to another location */ if (_velocity_xy_filtered < 5 && _velocity_z_filtered < 10 && _airspeed_filtered < 10) { _local_pos.landed = true; } else { _local_pos.landed = false; } _local_pos.z_global = false; _local_pos.yaw = _att.yaw; /* lazily publish the local position only once available */ if (_local_pos_pub > 0) { /* publish the attitude setpoint */ orb_publish(ORB_ID(vehicle_local_position), _local_pos_pub, &_local_pos); } else { /* advertise and publish */ _local_pos_pub = orb_advertise(ORB_ID(vehicle_local_position), &_local_pos); } _global_pos.timestamp = _local_pos.timestamp; if (_local_pos.xy_global) { double est_lat, est_lon; map_projection_reproject(&_pos_ref, _local_pos.x, _local_pos.y, &est_lat, &est_lon); _global_pos.lat = est_lat; _global_pos.lon = est_lon; _global_pos.time_gps_usec = _gps.time_gps_usec; _global_pos.eph = _gps.eph; _global_pos.epv = _gps.epv; } if (_local_pos.v_xy_valid) { _global_pos.vel_n = _local_pos.vx; _global_pos.vel_e = _local_pos.vy; } else { _global_pos.vel_n = 0.0f; _global_pos.vel_e = 0.0f; } /* local pos alt is negative, change sign and add alt offsets */ _global_pos.alt = _baro_ref + (-_local_pos.z) - _baro_gps_offset; if (_local_pos.v_z_valid) { _global_pos.vel_d = _local_pos.vz; } _global_pos.yaw = _local_pos.yaw; _global_pos.eph = _gps.eph; _global_pos.epv = _gps.epv; _global_pos.timestamp = _local_pos.timestamp; /* lazily publish the global position only once available */ if (_global_pos_pub > 0) { /* publish the global position */ orb_publish(ORB_ID(vehicle_global_position), _global_pos_pub, &_global_pos); } else { /* advertise and publish */ _global_pos_pub = orb_advertise(ORB_ID(vehicle_global_position), &_global_pos); } if (hrt_elapsed_time(&_wind.timestamp) > 99000) { _wind.timestamp = _global_pos.timestamp; _wind.windspeed_north = _ekf->states[14]; _wind.windspeed_east = _ekf->states[15]; _wind.covariance_north = 0.0f; // XXX get form filter _wind.covariance_east = 0.0f; /* lazily publish the wind estimate only once available */ if (_wind_pub > 0) { /* publish the wind estimate */ orb_publish(ORB_ID(wind_estimate), _wind_pub, &_wind); } else { /* advertise and publish */ _wind_pub = orb_advertise(ORB_ID(wind_estimate), &_wind); } } } } if (hrt_elapsed_time(&_wind.timestamp) > 99000) { _wind.timestamp = _global_pos.timestamp; _wind.windspeed_north = _ekf->states[14]; _wind.windspeed_east = _ekf->states[15]; _wind.covariance_north = _ekf->P[14][14]; _wind.covariance_east = _ekf->P[15][15]; /* lazily publish the wind estimate only once available */ if (_wind_pub > 0) { /* publish the wind estimate */ orb_publish(ORB_ID(wind_estimate), _wind_pub, &_wind); } else { /* advertise and publish */ _wind_pub = orb_advertise(ORB_ID(wind_estimate), &_wind); } } } } perf_end(_loop_perf); } warnx("exiting.\n"); _estimator_task = -1; _exit(0); }
void *nmea_loop(void *args) { /* Set thread name */ prctl(PR_SET_NAME, "gps nmea read", getpid()); /* Retrieve file descriptor and thread flag */ struct arg_struct *arguments = (struct arg_struct *)args; int *fd = arguments->fd_ptr; bool *thread_should_exit = arguments->thread_should_exit_ptr; /* Initialize gps stuff */ nmeaINFO info_d; nmeaINFO *info = &info_d; char gps_rx_buffer[NMEA_BUFFER_SIZE]; /* gps parser (nmea) */ nmeaPARSER parser; nmea_parser_init(&parser); nmea_zero_INFO(info); /* advertise GPS topic */ struct vehicle_gps_position_s nmea_gps_d = {.counter=0}; nmea_gps = &nmea_gps_d; orb_advert_t gps_handle = orb_advertise(ORB_ID(vehicle_gps_position), nmea_gps); while (!(*thread_should_exit)) { /* Parse a message from the gps receiver */ uint8_t read_res = read_gps_nmea(fd, gps_rx_buffer, NMEA_BUFFER_SIZE, info, &parser); if (0 == read_res) { /* convert data, ready it for publishing */ /* convert nmea utc time to usec */ struct tm timeinfo; timeinfo.tm_year = info->utc.year; timeinfo.tm_mon = info->utc.mon; timeinfo.tm_mday = info->utc.day; timeinfo.tm_hour = info->utc.hour; timeinfo.tm_min = info->utc.min; timeinfo.tm_sec = info->utc.sec; time_t epoch = mktime(&timeinfo); // printf("%d.%d.%d %d:%d:%d:%d\n", timeinfo.tm_year, timeinfo.tm_mon, timeinfo.tm_mday, timeinfo.tm_hour, timeinfo.tm_min, timeinfo.tm_sec, info->utc.hsec); nmea_gps->timestamp = hrt_absolute_time(); nmea_gps->time_gps_usec = (uint64_t)((epoch)*1000000 + (info->utc.hsec)*10000); nmea_gps->fix_type = (uint8_t)info->fix; nmea_gps->lat = (int32_t)(ndeg2degree(info->lat) * 1e7f); nmea_gps->lon = (int32_t)(ndeg2degree(info->lon) * 1e7f); nmea_gps->alt = (int32_t)(info->elv * 1000.0f); nmea_gps->eph = (uint16_t)(info->HDOP * 100); //TODO:test scaling nmea_gps->epv = (uint16_t)(info->VDOP * 100); //TODO:test scaling nmea_gps->vel = (uint16_t)(info->speed * 1000 / 36); //*1000/3600*100 nmea_gps->cog = (uint16_t)info->direction*100; //nmea: degrees float, ubx/mavlink: degrees*1e2 nmea_gps->satellites_visible = (uint8_t)info->satinfo.inview; int i = 0; /* Write info about individual satellites */ for (i = 0; i < 12; i++) { nmea_gps->satellite_prn[i] = (uint8_t)info->satinfo.sat[i].id; nmea_gps->satellite_used[i] = (uint8_t)info->satinfo.sat[i].in_use; nmea_gps->satellite_elevation[i] = (uint8_t)info->satinfo.sat[i].elv; nmea_gps->satellite_azimuth[i] = (uint8_t)info->satinfo.sat[i].azimuth; nmea_gps->satellite_snr[i] = (uint8_t)info->satinfo.sat[i].sig; } if (nmea_gps->satellites_visible > 0) { nmea_gps->satellite_info_available = 1; } else { nmea_gps->satellite_info_available = 0; } nmea_gps->counter_pos_valid++; nmea_gps->timestamp = hrt_absolute_time(); nmea_gps->counter++; pthread_mutex_lock(nmea_mutex); nmea_state->last_message_timestamp = hrt_absolute_time(); pthread_mutex_unlock(nmea_mutex); /* publish new GPS position */ orb_publish(ORB_ID(vehicle_gps_position), gps_handle, nmea_gps); } else if (read_res == 2) { //termination /* de-advertise */ close(gps_handle); break; } } //destroy gps parser nmea_parser_destroy(&parser); if(gps_verbose) printf("[gps] nmea loop is going to terminate\n"); return NULL; } void *nmea_watchdog_loop(void *args) { /* Set thread name */ prctl(PR_SET_NAME, "gps nmea watchdog", getpid()); bool nmea_healthy = false; uint8_t nmea_fail_count = 0; uint8_t nmea_success_count = 0; bool once_ok = false; /* Retrieve file descriptor and thread flag */ struct arg_struct *arguments = (struct arg_struct *)args; //int *fd = arguments->fd_ptr; bool *thread_should_exit = arguments->thread_should_exit_ptr; int mavlink_fd = open(MAVLINK_LOG_DEVICE, 0); while (!(*thread_should_exit)) { // printf("nmea_watchdog_loop : while "); /* if we have no update for a long time print warning (in nmea mode there is no reconfigure) */ pthread_mutex_lock(nmea_mutex); uint64_t timestamp_now = hrt_absolute_time(); bool all_okay = true; if (timestamp_now - nmea_state->last_message_timestamp > NMEA_WATCHDOG_CRITICAL_TIME_MICROSECONDS) { all_okay = false; } pthread_mutex_unlock(nmea_mutex); if (!all_okay) { /* gps error */ nmea_fail_count++; // printf("nmea error, nmea_fail_count=%u\n", nmea_fail_count); // fflush(stdout); /* If we have too many failures and another mode or baud should be tried, exit... */ if ((gps_mode_try_all == true || gps_baud_try_all == true) && (nmea_fail_count >= NMEA_HEALTH_FAIL_COUNTER_LIMIT) && (nmea_healthy == false) && once_ok == false) { if (gps_verbose) printf("\t[gps] no NMEA module found\n"); gps_mode_success = false; break; } if (nmea_healthy && nmea_fail_count >= NMEA_HEALTH_FAIL_COUNTER_LIMIT) { printf("\t[gps] ERROR: NMEA GPS module stopped responding\n"); // global_data_send_subsystem_info(&nmea_present_enabled); mavlink_log_critical(mavlink_fd, "[gps] NMEA module stopped responding\n"); nmea_healthy = false; nmea_success_count = 0; } fflush(stdout); sleep(1); } else { /* gps healthy */ // printf("\t[gps] nmea success\n"); nmea_success_count++; if (!nmea_healthy && nmea_success_count >= NMEA_HEALTH_SUCCESS_COUNTER_LIMIT) { printf("[gps] NMEA module found, status ok (baud=%d)\r\n", current_gps_speed); // global_data_send_subsystem_info(&nmea_present_enabled_healthy); mavlink_log_info(mavlink_fd, "[gps] NMEA module found, status ok\n"); nmea_healthy = true; nmea_fail_count = 0; once_ok = true; } } usleep(NMEA_WATCHDOG_WAIT_TIME_MICROSECONDS); } if(gps_verbose) printf("[gps] nmea watchdog loop is going to terminate\n"); close(mavlink_fd); return NULL; }
int ROV_main(int argc, char *argv[]) { /* Initialize actuator struct and set it to zero*/ struct actuator_controls_s actuators; memset(&actuators, 0, sizeof(actuators)); /* Initialize armed struct and set ini values*/ struct actuator_armed_s armed; armed.armed = true; armed.lockdown = false; /* lock down actuators if required, only in HIL */ /* Advertise actuator and armed topics and publish ini values*/ orb_advert_t armed_pub = orb_advertise(ORB_ID(actuator_armed), &armed); orb_advert_t actuator_pub_fd = orb_advertise(ORB_ID(actuator_controls_0), &actuators); /* handlers for sensor and attitude (EKF) subscriptions */ int _v_att_sub = orb_subscribe(ORB_ID(vehicle_attitude)); int sensor_sub_fd = orb_subscribe(ORB_ID(sensor_combined)); int _bat_stat_sub = orb_subscribe(ORB_ID(battery_status)); orb_set_interval(sensor_sub_fd, 1000); /* Initialize aux variables and abs time variable */ int i ; int ret; char c_key; float rcvalue = 0.0f; hrt_abstime stime; //*******************data containers*********************************************************** struct vehicle_attitude_s _v_att; /**< vehicle attitude */ struct sensor_combined_s raw; /**< sensor values */ struct battery_status_s _bat_stat; /**< battery status */ /* Key pressed event */ struct pollfd fds; fds.fd = 0; /* stdin */ fds.events = POLLIN; // controller tuning parameters float k_ax = 0.1f; // gain for uprighting moment (pitch) float k_ay = 0.2f; // gain for roll compensator float c_ax = 0.5f; // gain for inverse influence on thrust and yaw when vehicle is not aligned in plane (x-axis) float c_ay = c_ax; // gain for inverse influence on thrust and yaw when vehicle is not aligned in plane (y-axis) float k_omz = 1.0f; // yaw rate gain float omz_set = 0.0f; // setpoint yaw rate float k_thrust = 1.0f; // forward thrust gain float thrust_set = 0.0f; // thrust setpoint /* Open PWM device driver*/ int fd = open(PWM_OUTPUT0_DEVICE_PATH, 0); /* Print to console */ printf("Start. Press g after ESCs ready. \n"); /* Main loop */ while (true) { /* start main loop by publishing zero values to actuators to start ESCs */ /* Publish zero */ for (i=0; i<4; i++){ actuators.control[i] = rcvalue; actuators.timestamp = hrt_absolute_time(); orb_publish(ORB_ID(actuator_armed), armed_pub, &armed); orb_publish(ORB_ID(actuator_controls_0), actuator_pub_fd, &actuators); } usleep(10000); /* Check whether key pressed */ ret = poll(&fds, 1, 0); if (ret > 0) { /* If key pressed event occured */ read(0, &c_key, 1); if (c_key == 0x67) { // If "g" key pressed go into key control loop warnx("Start\n"); stime = hrt_absolute_time(); /* Keyboard control. Can be aborted with "c" key */ while (true) { for (unsigned k = 0; k < 4; k++) { actuators.control[k] = 0.0f; } usleep(20000); ret = poll(&fds, 1, 0); fflush(stdin); if (ret > 0) { // If key pressed event occured read(0,&c_key,1); fflush(stdin); switch (c_key){ //User abort case 0x63: //c warnx("User abort\n"); //Stop servos for (i=0; i<4; i++){ actuators.control[i] = 0.0f; } actuators.timestamp = hrt_absolute_time(); orb_publish(ORB_ID(actuator_armed), armed_pub, &armed); orb_publish(ORB_ID(actuator_controls_0), actuator_pub_fd, &actuators); usleep(10000); exit(0); //return break; // Emergency stop case 0x20: // space actuators.control[0] = 0.0f; actuators.control[1] = 0.0f; actuators.control[2] = 0.0f; actuators.control[3] = 0.0f; break; // roll case 0x71: // q actuators.control[0] = -1.0f; break; case 0x65: // e actuators.control[0] = +1.0f; break; // pitch case 0x77: // w actuators.control[1] = -1.0f; break; case 0x73: // s actuators.control[1] = +1.0f; break; // yaw case 0x61: // a actuators.control[2] = -1.0f; break; case 0x64: // d actuators.control[2] = +1.0f; break; // Acc case 0x72: // r actuators.control[3] = +1.0f; break; // Rev. Acc case 0x66: // f actuators.control[3] = -1.0f; break; // gyro & acc stabilized mode // keyboard control centered around j - neutral h,g left, k,l right, one/two row up forward, one row down backward default: switch (c_key){ // neutral position stabilizing case 0x6A: // j thrust_set = 0.0f; omz_set = 0.0f; break; // slow left case 0x68: // h thrust_set = 0.0f; omz_set = -0.4f; break; // hard left case 0x67: // g thrust_set = 0.0f; omz_set = -1.0f; break; // slow right case 0x6B: // k thrust_set = 0.0f; omz_set = 0.4f; break; // hard right case 0x6C: // l thrust_set = 0.0f; omz_set = 1.0f; break; // forward case 0x75: // u thrust_set = 0.3f; omz_set = 0.0f; break; // forward slow left case 0x7A: // z thrust_set = 0.3f; omz_set = -0.4f; break; // forward hard left case 0x74: // t thrust_set = 0.3f; omz_set = -1.0f; break; // forward slow right case 0x69: // i thrust_set = 0.3f; omz_set = 0.4f; break; // forward hard right case 0x6F: // o thrust_set = 0.3f; omz_set = 1.0f; break; // backward case 0x6D: // m thrust_set = -0.3f; omz_set = 0.0f; break; // backward slow left case 0x6E: // n thrust_set = -0.3f; omz_set = -0.4f; break; // backward hard left case 0x62: // b thrust_set = -0.3f; omz_set = -1.0f; break; // backward slow right case 0x2C: // , thrust_set = -0.3f; omz_set = 0.4f; break; // backward hard right case 0x2E: // . thrust_set = -0.3f; omz_set = 1.0f; break; case 0x55: // U thrust gain +.1 k_thrust = k_thrust + 0.1f; printf("thrust gain +.1 - k_thrust = %8.4f",(double)k_thrust); break; case 0x4D: // M thrust gain -.1 k_thrust = k_thrust - 0.1f; printf("thrust gain -.1 - k_thrust = %8.4f",(double)k_thrust); break; case 0x4B: // K yaw rate gain +.1 k_omz = k_omz + 0.1f; printf("yaw rate gain +.1 - k_omz = %8.4f",(double)k_omz); break; case 0x48: // H yaw rate gain -.1 k_omz = k_omz - 0.1f; printf("yaw rate gain -.1 - k_omz = %8.4f",(double)k_omz); break; case 0x5A: // Z pitch stabilizer gain +.1 k_ax = k_ax + 0.1f; printf("pitch stabilizer gain +.1 - k_ax = %8.4f",(double)k_ax); break; case 0x4E: // N pitch stabilizer gain -.1 k_ax = k_ax - 0.1f; printf("pitch stabilizer gain -.1 - k_ax = %8.4f",(double)k_ax); break; case 0x54: // T roll stabilizer gain +.1 k_ay = k_ay + 0.1f; printf("roll stabilizer gain +.1 - k_ay = %8.4f",(double)k_ay); break; case 0x42: // B roll stabilizer gain -.1 k_ay = k_ay - 0.1f; printf("roll stabilizer gain -.1 - k_ay = %8.4f",(double)k_ay); break; case 0x49: // I pitch stabilizer dominance +.025 c_ax = c_ax + 0.025f; printf("pitch stabilizer dominance +.025 - c_ax = %8.4f",(double)c_ax); break; case 0x3B: // ; pitch stabilizer dominance -.025 c_ax = c_ax - 0.025f; printf("pitch stabilizer dominance -.025 - c_ax = %8.4f",(double)c_ax); break; case 0x4F: // O roll stabilizer dominance +.1 c_ay = c_ay + 0.1f; printf("roll stabilizer dominance +.1 - c_ay = %8.4f",(double)c_ay); break; case 0x3A: // : roll stabilizer dominance -.1 c_ay = c_ay - 0.1f; printf("roll stabilizer dominance -.1 - c_ay = %8.4f",(double)c_ay); break; default: printf("Unidentified key pressed: %c",c_key); thrust_set = 0.0f; omz_set = 0.0f; actuators.control[0] = 0.0f; actuators.control[1] = 0.0f; actuators.control[2] = 0.0f; actuators.control[3] = 0.0f; break; } // gyro controlled // copy sensors raw data into local buffer orb_copy(ORB_ID(sensor_combined), sensor_sub_fd, &raw); // roll moment when y-axis is not horizontal actuators.control[0] = k_ay * raw.accelerometer_m_s2[1]; // pitch moment when x-axis is not horizontal actuators.control[1] = k_ax * raw.accelerometer_m_s2[0]; // yaw moment when omz not omz_set and y and x axes are in horizontal plane actuators.control[2] = k_omz * (omz_set - raw.gyro1_rad_s[2]) /(1+abs(c_ax*raw.accelerometer_m_s2[0])+abs(c_ay*raw.accelerometer_m_s2[1])); // forward thrust when nose is directed horizontally actuators.control[3] = k_thrust * thrust_set /(1+abs(c_ax*raw.accelerometer_m_s2[0])+abs(c_ay*raw.accelerometer_m_s2[1])); break; // default /* // Emergency stop case 0x70: // p actuators.control[0] = 0.0f; actuators.control[1] = 0.0f; actuators.control[2] = 0.0f; actuators.control[3] = 0.0f; break;*/ } } /* sanity check and publish actuator outputs */ if (isfinite(actuators.control[0]) && isfinite(actuators.control[1]) && isfinite(actuators.control[2]) && isfinite(actuators.control[3])) { actuators.timestamp = hrt_absolute_time(); orb_publish(ORB_ID(actuator_armed), armed_pub, &armed); orb_publish(ORB_ID(actuator_controls_0), actuator_pub_fd, &actuators); } /* copy attitude topic which is produced by attitude estimator */ orb_copy(ORB_ID(vehicle_attitude), _v_att_sub, &_v_att); /* copy sensors raw data into local buffer */ orb_copy(ORB_ID(sensor_combined), sensor_sub_fd, &raw); /* copy battery status into local buffer */ orb_copy(ORB_ID(battery_status), _bat_stat_sub, &_bat_stat); /* Plot to terminal */ if (hrt_absolute_time() - stime > 500000){ /* Plot pwm values */ for (unsigned k = 0; k < 4; k++) { servo_position_t spos; ret = ioctl(fd, PWM_SERVO_GET(k), (unsigned long)&spos); if (ret == OK) { printf("pwm channel %u: %u us\n", k+1, spos); } } /* Print sensor & EKF values */ // printf("Snrs:\n Pres:\t%8.4f\n", // (double)raw.baro_pres_mbar); // // printf("Temp:\t%8.4f\n", // (double)raw.baro_temp_celcius); // printf("Ang:\t%8.4f\t%8.4f\t%8.4f\n", (double)_v_att.roll, (double)_v_att.pitch, (double)_v_att.yaw); printf("Vel:\t%8.4f\t%8.4f\t%8.4f\n", (double)_v_att.rollspeed, (double)_v_att.pitchspeed, (double)_v_att.yawspeed); printf("Acc:\t%8.4f\t%8.4f\t%8.4f\n \n", (double)_v_att.rollacc, (double)_v_att.pitchacc, (double)_v_att.yawacc); printf("ADC 10:\t%8.4f\n", (double)raw.adc_voltage_v[6]); printf("BAT:\t%8.4f\n \n", (double)_bat_stat.voltage_filtered_v); stime = hrt_absolute_time(); } fflush( stdout ); usleep(10000); } } } } return OK; }
void ADC::update_system_power(hrt_abstime now) { #if defined (BOARD_ADC_USB_CONNECTED) system_power_s system_power = {}; system_power.timestamp = now; system_power.voltage5v_v = 0; system_power.voltage3v3_v = 0; system_power.v3v3_valid = 0; /* Assume HW provides only ADC_SCALED_V5_SENSE */ int cnt = 1; /* HW provides both ADC_SCALED_V5_SENSE and ADC_SCALED_V3V3_SENSORS_SENSE */ # if defined(ADC_SCALED_V5_SENSE) && defined(ADC_SCALED_V3V3_SENSORS_SENSE) cnt++; # endif for (unsigned i = 0; i < _channel_count; i++) { # if defined(ADC_SCALED_V5_SENSE) if (_samples[i].am_channel == ADC_SCALED_V5_SENSE) { // it is 2:1 scaled system_power.voltage5v_v = _samples[i].am_data * (ADC_V5_V_FULL_SCALE / 4096.0f); cnt--; } else # endif # if defined(ADC_SCALED_V3V3_SENSORS_SENSE) { if (_samples[i].am_channel == ADC_SCALED_V3V3_SENSORS_SENSE) { // it is 2:1 scaled system_power.voltage3v3_v = _samples[i].am_data * (ADC_3V3_SCALE * (3.3f / 4096.0f)); system_power.v3v3_valid = 1; cnt--; } } # endif if (cnt == 0) { break; } } /* Note once the board_config.h provides BOARD_ADC_USB_CONNECTED, * It must provide the true logic GPIO BOARD_ADC_xxxx macros. */ // these are not ADC related, but it is convenient to // publish these to the same topic system_power.usb_connected = BOARD_ADC_USB_CONNECTED; /* If provided used the Valid signal from HW*/ #if defined(BOARD_ADC_USB_VALID) system_power.usb_valid = BOARD_ADC_USB_VALID; #else /* If not provided then use connected */ system_power.usb_valid = system_power.usb_connected; #endif /* The valid signals (HW dependent) are associated with each brick */ bool valid_chan[BOARD_NUMBER_BRICKS] = BOARD_BRICK_VALID_LIST; system_power.brick_valid = 0; for (int b = 0; b < BOARD_NUMBER_BRICKS; b++) { system_power.brick_valid |= valid_chan[b] ? 1 << b : 0; } system_power.servo_valid = BOARD_ADC_SERVO_VALID; // OC pins are active low system_power.periph_5v_oc = BOARD_ADC_PERIPH_5V_OC; system_power.hipower_5v_oc = BOARD_ADC_HIPOWER_5V_OC; /* lazily publish */ if (_to_system_power != nullptr) { orb_publish(ORB_ID(system_power), _to_system_power, &system_power); } else { _to_system_power = orb_advertise(ORB_ID(system_power), &system_power); } #endif // BOARD_ADC_USB_CONNECTED }
static void handle_message(mavlink_message_t *msg) { if (msg->msgid == MAVLINK_MSG_ID_COMMAND_LONG) { mavlink_command_long_t cmd_mavlink; mavlink_msg_command_long_decode(msg, &cmd_mavlink); if (cmd_mavlink.target_system == mavlink_system.sysid && ((cmd_mavlink.target_component == mavlink_system.compid) || (cmd_mavlink.target_component == MAV_COMP_ID_ALL))) { //check for MAVLINK terminate command if (cmd_mavlink.command == MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN && ((int)cmd_mavlink.param1) == 3) { /* This is the link shutdown command, terminate mavlink */ printf("[mavlink] Terminating .. \n"); fflush(stdout); usleep(50000); /* terminate other threads and this thread */ thread_should_exit = true; } else { /* Copy the content of mavlink_command_long_t cmd_mavlink into command_t cmd */ vcmd.param1 = cmd_mavlink.param1; vcmd.param2 = cmd_mavlink.param2; vcmd.param3 = cmd_mavlink.param3; vcmd.param4 = cmd_mavlink.param4; vcmd.param5 = cmd_mavlink.param5; vcmd.param6 = cmd_mavlink.param6; vcmd.param7 = cmd_mavlink.param7; vcmd.command = cmd_mavlink.command; vcmd.target_system = cmd_mavlink.target_system; vcmd.target_component = cmd_mavlink.target_component; vcmd.source_system = msg->sysid; vcmd.source_component = msg->compid; vcmd.confirmation = cmd_mavlink.confirmation; /* check if topic is advertised */ if (cmd_pub <= 0) { cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd); } /* publish */ orb_publish(ORB_ID(vehicle_command), cmd_pub, &vcmd); } } } if (msg->msgid == MAVLINK_MSG_ID_OPTICAL_FLOW) { mavlink_optical_flow_t flow; mavlink_msg_optical_flow_decode(msg, &flow); struct optical_flow_s f; f.timestamp = flow.time_usec; f.flow_raw_x = flow.flow_x; f.flow_raw_y = flow.flow_y; f.flow_comp_x_m = flow.flow_comp_m_x; f.flow_comp_y_m = flow.flow_comp_m_y; f.ground_distance_m = flow.ground_distance; f.quality = flow.quality; f.sensor_id = flow.sensor_id; /* check if topic is advertised */ if (flow_pub <= 0) { flow_pub = orb_advertise(ORB_ID(optical_flow), &f); } else { /* publish */ orb_publish(ORB_ID(optical_flow), flow_pub, &f); } } if (msg->msgid == MAVLINK_MSG_ID_SET_MODE) { /* Set mode on request */ mavlink_set_mode_t new_mode; mavlink_msg_set_mode_decode(msg, &new_mode); /* Copy the content of mavlink_command_long_t cmd_mavlink into command_t cmd */ vcmd.param1 = new_mode.base_mode; vcmd.param2 = new_mode.custom_mode; vcmd.param3 = 0; vcmd.param4 = 0; vcmd.param5 = 0; vcmd.param6 = 0; vcmd.param7 = 0; vcmd.command = MAV_CMD_DO_SET_MODE; vcmd.target_system = new_mode.target_system; vcmd.target_component = MAV_COMP_ID_ALL; vcmd.source_system = msg->sysid; vcmd.source_component = msg->compid; vcmd.confirmation = 1; /* check if topic is advertised */ if (cmd_pub <= 0) { cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd); } else { /* create command */ orb_publish(ORB_ID(vehicle_command), cmd_pub, &vcmd); } } /* Handle Vicon position estimates */ if (msg->msgid == MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE) { mavlink_vicon_position_estimate_t pos; mavlink_msg_vicon_position_estimate_decode(msg, &pos); vicon_position.timestamp = hrt_absolute_time(); vicon_position.x = pos.x; vicon_position.y = pos.y; vicon_position.z = pos.z; vicon_position.roll = pos.roll; vicon_position.pitch = pos.pitch; vicon_position.yaw = pos.yaw; if (vicon_position_pub <= 0) { vicon_position_pub = orb_advertise(ORB_ID(vehicle_vicon_position), &vicon_position); } else { orb_publish(ORB_ID(vehicle_vicon_position), vicon_position_pub, &vicon_position); } } /* Handle quadrotor motor setpoints */ if (msg->msgid == MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST) { mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t quad_motors_setpoint; mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(msg, &quad_motors_setpoint); if (mavlink_system.sysid < 4) { /* switch to a receiving link mode */ gcs_link = false; /* * rate control mode - defined by MAVLink */ uint8_t ml_mode = 0; bool ml_armed = false; switch (quad_motors_setpoint.mode) { case 0: ml_armed = false; break; case 1: ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_RATES; ml_armed = true; break; case 2: ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE; ml_armed = true; break; case 3: ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY; break; case 4: ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_POSITION; break; } offboard_control_sp.p1 = (float)quad_motors_setpoint.roll[mavlink_system.sysid - 1] / (float)INT16_MAX; offboard_control_sp.p2 = (float)quad_motors_setpoint.pitch[mavlink_system.sysid - 1] / (float)INT16_MAX; offboard_control_sp.p3 = (float)quad_motors_setpoint.yaw[mavlink_system.sysid - 1] / (float)INT16_MAX; offboard_control_sp.p4 = (float)quad_motors_setpoint.thrust[mavlink_system.sysid - 1] / (float)UINT16_MAX; if (quad_motors_setpoint.thrust[mavlink_system.sysid - 1] == 0) { ml_armed = false; } offboard_control_sp.armed = ml_armed; offboard_control_sp.mode = ml_mode; offboard_control_sp.timestamp = hrt_absolute_time(); /* check if topic has to be advertised */ if (offboard_control_sp_pub <= 0) { offboard_control_sp_pub = orb_advertise(ORB_ID(offboard_control_setpoint), &offboard_control_sp); } else { /* Publish */ orb_publish(ORB_ID(offboard_control_setpoint), offboard_control_sp_pub, &offboard_control_sp); } } } /* * Only decode hil messages in HIL mode. * * The HIL mode is enabled by the HIL bit flag * in the system mode. Either send a set mode * COMMAND_LONG message or a SET_MODE message */ if (mavlink_hil_enabled) { uint64_t timestamp = hrt_absolute_time(); /* TODO, set ground_press/ temp during calib */ static const float ground_press = 1013.25f; // mbar static const float ground_tempC = 21.0f; static const float ground_alt = 0.0f; static const float T0 = 273.15; static const float R = 287.05f; static const float g = 9.806f; if (msg->msgid == MAVLINK_MSG_ID_RAW_IMU) { mavlink_raw_imu_t imu; mavlink_msg_raw_imu_decode(msg, &imu); /* packet counter */ static uint16_t hil_counter = 0; static uint16_t hil_frames = 0; static uint64_t old_timestamp = 0; /* sensors general */ hil_sensors.timestamp = imu.time_usec; /* hil gyro */ static const float mrad2rad = 1.0e-3f; hil_sensors.gyro_counter = hil_counter; hil_sensors.gyro_raw[0] = imu.xgyro; hil_sensors.gyro_raw[1] = imu.ygyro; hil_sensors.gyro_raw[2] = imu.zgyro; hil_sensors.gyro_rad_s[0] = imu.xgyro * mrad2rad; hil_sensors.gyro_rad_s[1] = imu.ygyro * mrad2rad; hil_sensors.gyro_rad_s[2] = imu.zgyro * mrad2rad; /* accelerometer */ hil_sensors.accelerometer_counter = hil_counter; static const float mg2ms2 = 9.8f / 1000.0f; hil_sensors.accelerometer_raw[0] = imu.xacc; hil_sensors.accelerometer_raw[1] = imu.yacc; hil_sensors.accelerometer_raw[2] = imu.zacc; hil_sensors.accelerometer_m_s2[0] = mg2ms2 * imu.xacc; hil_sensors.accelerometer_m_s2[1] = mg2ms2 * imu.yacc; hil_sensors.accelerometer_m_s2[2] = mg2ms2 * imu.zacc; hil_sensors.accelerometer_mode = 0; // TODO what is this? hil_sensors.accelerometer_range_m_s2 = 32.7f; // int16 /* adc */ hil_sensors.adc_voltage_v[0] = 0; hil_sensors.adc_voltage_v[1] = 0; hil_sensors.adc_voltage_v[2] = 0; /* magnetometer */ float mga2ga = 1.0e-3f; hil_sensors.magnetometer_counter = hil_counter; hil_sensors.magnetometer_raw[0] = imu.xmag; hil_sensors.magnetometer_raw[1] = imu.ymag; hil_sensors.magnetometer_raw[2] = imu.zmag; hil_sensors.magnetometer_ga[0] = imu.xmag * mga2ga; hil_sensors.magnetometer_ga[1] = imu.ymag * mga2ga; hil_sensors.magnetometer_ga[2] = imu.zmag * mga2ga; hil_sensors.magnetometer_range_ga = 32.7f; // int16 hil_sensors.magnetometer_mode = 0; // TODO what is this hil_sensors.magnetometer_cuttoff_freq_hz = 50.0f; /* publish */ orb_publish(ORB_ID(sensor_combined), pub_hil_sensors, &hil_sensors); // increment counters hil_counter += 1 ; hil_frames += 1 ; // output if ((timestamp - old_timestamp) > 10000000) { printf("receiving hil imu at %d hz\n", hil_frames/10); old_timestamp = timestamp; hil_frames = 0; } } if (msg->msgid == MAVLINK_MSG_ID_HIGHRES_IMU) { mavlink_highres_imu_t imu; mavlink_msg_highres_imu_decode(msg, &imu); /* packet counter */ static uint16_t hil_counter = 0; static uint16_t hil_frames = 0; static uint64_t old_timestamp = 0; /* sensors general */ hil_sensors.timestamp = hrt_absolute_time(); /* hil gyro */ static const float mrad2rad = 1.0e-3f; hil_sensors.gyro_counter = hil_counter; hil_sensors.gyro_raw[0] = imu.xgyro / mrad2rad; hil_sensors.gyro_raw[1] = imu.ygyro / mrad2rad; hil_sensors.gyro_raw[2] = imu.zgyro / mrad2rad; hil_sensors.gyro_rad_s[0] = imu.xgyro; hil_sensors.gyro_rad_s[1] = imu.ygyro; hil_sensors.gyro_rad_s[2] = imu.zgyro; /* accelerometer */ hil_sensors.accelerometer_counter = hil_counter; static const float mg2ms2 = 9.8f / 1000.0f; hil_sensors.accelerometer_raw[0] = imu.xacc / mg2ms2; hil_sensors.accelerometer_raw[1] = imu.yacc / mg2ms2; hil_sensors.accelerometer_raw[2] = imu.zacc / mg2ms2; hil_sensors.accelerometer_m_s2[0] = imu.xacc; hil_sensors.accelerometer_m_s2[1] = imu.yacc; hil_sensors.accelerometer_m_s2[2] = imu.zacc; hil_sensors.accelerometer_mode = 0; // TODO what is this? hil_sensors.accelerometer_range_m_s2 = 32.7f; // int16 /* adc */ hil_sensors.adc_voltage_v[0] = 0; hil_sensors.adc_voltage_v[1] = 0; hil_sensors.adc_voltage_v[2] = 0; /* magnetometer */ float mga2ga = 1.0e-3f; hil_sensors.magnetometer_counter = hil_counter; hil_sensors.magnetometer_raw[0] = imu.xmag / mga2ga; hil_sensors.magnetometer_raw[1] = imu.ymag / mga2ga; hil_sensors.magnetometer_raw[2] = imu.zmag / mga2ga; hil_sensors.magnetometer_ga[0] = imu.xmag; hil_sensors.magnetometer_ga[1] = imu.ymag; hil_sensors.magnetometer_ga[2] = imu.zmag; hil_sensors.magnetometer_range_ga = 32.7f; // int16 hil_sensors.magnetometer_mode = 0; // TODO what is this hil_sensors.magnetometer_cuttoff_freq_hz = 50.0f; hil_sensors.baro_pres_mbar = imu.abs_pressure; float tempC = imu.temperature; float tempAvgK = T0 + (tempC + ground_tempC) / 2.0f; float h = ground_alt + (R / g) * tempAvgK * logf(ground_press / imu.abs_pressure); hil_sensors.baro_alt_meter = h; hil_sensors.baro_temp_celcius = imu.temperature; hil_sensors.gyro_counter = hil_counter; hil_sensors.magnetometer_counter = hil_counter; hil_sensors.accelerometer_counter = hil_counter; /* publish */ orb_publish(ORB_ID(sensor_combined), pub_hil_sensors, &hil_sensors); // increment counters hil_counter++; hil_frames++; // output if ((timestamp - old_timestamp) > 10000000) { printf("receiving hil imu at %d hz\n", hil_frames/10); old_timestamp = timestamp; hil_frames = 0; } } if (msg->msgid == MAVLINK_MSG_ID_GPS_RAW_INT) { mavlink_gps_raw_int_t gps; mavlink_msg_gps_raw_int_decode(msg, &gps); /* packet counter */ static uint16_t hil_counter = 0; static uint16_t hil_frames = 0; static uint64_t old_timestamp = 0; /* gps */ hil_gps.timestamp_position = gps.time_usec; hil_gps.time_gps_usec = gps.time_usec; hil_gps.lat = gps.lat; hil_gps.lon = gps.lon; hil_gps.alt = gps.alt; hil_gps.eph_m = (float)gps.eph * 1e-2f; // from cm to m hil_gps.epv_m = (float)gps.epv * 1e-2f; // from cm to m hil_gps.s_variance_m_s = 5.0f; hil_gps.p_variance_m = hil_gps.eph_m * hil_gps.eph_m; hil_gps.vel_m_s = (float)gps.vel * 1e-2f; // from cm/s to m/s /* gps.cog is in degrees 0..360 * 100, heading is -PI..+PI */ float heading_rad = gps.cog * M_DEG_TO_RAD_F * 1e-2f; /* go back to -PI..PI */ if (heading_rad > M_PI_F) heading_rad -= 2.0f * M_PI_F; hil_gps.vel_n_m_s = (float)gps.vel * 1e-2f * cosf(heading_rad); hil_gps.vel_e_m_s = (float)gps.vel * 1e-2f * sinf(heading_rad); hil_gps.vel_d_m_s = 0.0f; hil_gps.vel_ned_valid = true; /* COG (course over ground) is speced as -PI..+PI */ hil_gps.cog_rad = heading_rad; hil_gps.fix_type = gps.fix_type; hil_gps.satellites_visible = gps.satellites_visible; /* publish */ orb_publish(ORB_ID(vehicle_gps_position), pub_hil_gps, &hil_gps); // increment counters hil_counter += 1 ; hil_frames += 1 ; // output if ((timestamp - old_timestamp) > 10000000) { printf("receiving hil gps at %d hz\n", hil_frames/10); old_timestamp = timestamp; hil_frames = 0; } } if (msg->msgid == MAVLINK_MSG_ID_RAW_PRESSURE) { mavlink_raw_pressure_t press; mavlink_msg_raw_pressure_decode(msg, &press); /* packet counter */ static uint16_t hil_counter = 0; static uint16_t hil_frames = 0; static uint64_t old_timestamp = 0; /* sensors general */ hil_sensors.timestamp = press.time_usec; /* baro */ float tempC = press.temperature / 100.0f; float tempAvgK = T0 + (tempC + ground_tempC) / 2.0f; float h = ground_alt + (R / g) * tempAvgK * logf(ground_press / press.press_abs); hil_sensors.baro_counter = hil_counter; hil_sensors.baro_pres_mbar = press.press_abs; hil_sensors.baro_alt_meter = h; hil_sensors.baro_temp_celcius = tempC; /* publish */ orb_publish(ORB_ID(sensor_combined), pub_hil_sensors, &hil_sensors); // increment counters hil_counter += 1 ; hil_frames += 1 ; // output if ((timestamp - old_timestamp) > 10000000) { printf("receiving hil pressure at %d hz\n", hil_frames/10); old_timestamp = timestamp; hil_frames = 0; } } if (msg->msgid == MAVLINK_MSG_ID_HIL_STATE) { mavlink_hil_state_t hil_state; mavlink_msg_hil_state_decode(msg, &hil_state); /* Calculate Rotation Matrix */ //TODO: better clarification which app does this, atm we have a ekf for quadrotors which does this, but there is no such thing if fly in fixed wing mode if (mavlink_system.type == MAV_TYPE_FIXED_WING) { //TODO: assuming low pitch and roll values for now hil_attitude.R[0][0] = cosf(hil_state.yaw); hil_attitude.R[0][1] = sinf(hil_state.yaw); hil_attitude.R[0][2] = 0.0f; hil_attitude.R[1][0] = -sinf(hil_state.yaw); hil_attitude.R[1][1] = cosf(hil_state.yaw); hil_attitude.R[1][2] = 0.0f; hil_attitude.R[2][0] = 0.0f; hil_attitude.R[2][1] = 0.0f; hil_attitude.R[2][2] = 1.0f; hil_attitude.R_valid = true; } hil_global_pos.lat = hil_state.lat; hil_global_pos.lon = hil_state.lon; hil_global_pos.alt = hil_state.alt / 1000.0f; hil_global_pos.vx = hil_state.vx / 100.0f; hil_global_pos.vy = hil_state.vy / 100.0f; hil_global_pos.vz = hil_state.vz / 100.0f; /* set timestamp and notify processes (broadcast) */ hil_global_pos.timestamp = hrt_absolute_time(); orb_publish(ORB_ID(vehicle_global_position), pub_hil_global_pos, &hil_global_pos); hil_attitude.roll = hil_state.roll; hil_attitude.pitch = hil_state.pitch; hil_attitude.yaw = hil_state.yaw; hil_attitude.rollspeed = hil_state.rollspeed; hil_attitude.pitchspeed = hil_state.pitchspeed; hil_attitude.yawspeed = hil_state.yawspeed; /* set timestamp and notify processes (broadcast) */ hil_attitude.timestamp = hrt_absolute_time(); orb_publish(ORB_ID(vehicle_attitude), pub_hil_attitude, &hil_attitude); } if (msg->msgid == MAVLINK_MSG_ID_MANUAL_CONTROL) { mavlink_manual_control_t man; mavlink_msg_manual_control_decode(msg, &man); struct rc_channels_s rc_hil; memset(&rc_hil, 0, sizeof(rc_hil)); static orb_advert_t rc_pub = 0; rc_hil.timestamp = hrt_absolute_time(); rc_hil.chan_count = 4; rc_hil.chan[0].scaled = man.x / 1000.0f; rc_hil.chan[1].scaled = man.y / 1000.0f; rc_hil.chan[2].scaled = man.r / 1000.0f; rc_hil.chan[3].scaled = man.z / 1000.0f; struct manual_control_setpoint_s mc; static orb_advert_t mc_pub = 0; int manual_sub = orb_subscribe(ORB_ID(manual_control_setpoint)); /* get a copy first, to prevent altering values that are not sent by the mavlink command */ orb_copy(ORB_ID(manual_control_setpoint), manual_sub, &mc); mc.timestamp = rc_hil.timestamp; mc.roll = man.x / 1000.0f; mc.pitch = man.y / 1000.0f; mc.yaw = man.r / 1000.0f; mc.throttle = man.z / 1000.0f; /* fake RC channels with manual control input from simulator */ if (rc_pub == 0) { rc_pub = orb_advertise(ORB_ID(rc_channels), &rc_hil); } else { orb_publish(ORB_ID(rc_channels), rc_pub, &rc_hil); } if (mc_pub == 0) { mc_pub = orb_advertise(ORB_ID(manual_control_setpoint), &mc); } else { orb_publish(ORB_ID(manual_control_setpoint), mc_pub, &mc); } } } }
CameraTrigger::CameraTrigger() : _engagecall {}, _disengagecall {}, _engage_turn_on_off_call {}, _disengage_turn_on_off_call {}, _keepalivecall_up {}, _keepalivecall_down {}, _activation_time(0.5f /* ms */), _interval(100.0f /* ms */), _distance(25.0f /* m */), _trigger_seq(0), _trigger_enabled(false), _trigger_paused(false), _one_shot(false), _test_shot(false), _turning_on(false), _last_shoot_position(0.0f, 0.0f), _valid_position(false), _command_sub(-1), _lpos_sub(-1), _trigger_pub(nullptr), _cmd_ack_pub(nullptr), _trigger_mode(TRIGGER_MODE_NONE), _camera_interface_mode(CAMERA_INTERFACE_MODE_GPIO), _camera_interface(nullptr) { // Initiate camera interface based on camera_interface_mode if (_camera_interface != nullptr) { delete (_camera_interface); // set to zero to ensure parser is not used while not instantiated _camera_interface = nullptr; } memset(&_work, 0, sizeof(_work)); // Parameters _p_interval = param_find("TRIG_INTERVAL"); _p_distance = param_find("TRIG_DISTANCE"); _p_activation_time = param_find("TRIG_ACT_TIME"); _p_mode = param_find("TRIG_MODE"); _p_interface = param_find("TRIG_INTERFACE"); param_get(_p_activation_time, &_activation_time); param_get(_p_interval, &_interval); param_get(_p_distance, &_distance); param_get(_p_mode, &_trigger_mode); param_get(_p_interface, &_camera_interface_mode); switch (_camera_interface_mode) { #ifdef __PX4_NUTTX case CAMERA_INTERFACE_MODE_GPIO: _camera_interface = new CameraInterfaceGPIO(); break; case CAMERA_INTERFACE_MODE_GENERIC_PWM: _camera_interface = new CameraInterfacePWM(); break; case CAMERA_INTERFACE_MODE_SEAGULL_MAP2_PWM: _camera_interface = new CameraInterfaceSeagull(); break; #endif case CAMERA_INTERFACE_MODE_MAVLINK: // start an interface that does nothing. Instead mavlink will listen to the camera_trigger uORB message _camera_interface = new CameraInterface(); break; default: PX4_ERR("unknown camera interface mode: %i", (int)_camera_interface_mode); break; } // Enforce a lower bound on the activation interval in PWM modes to not miss // engage calls in-between 50Hz PWM pulses. (see PX4 PR #6973) if ((_activation_time < 40.0f) && (_camera_interface_mode == CAMERA_INTERFACE_MODE_GENERIC_PWM || _camera_interface_mode == CAMERA_INTERFACE_MODE_SEAGULL_MAP2_PWM)) { _activation_time = 40.0f; PX4_WARN("Trigger interval too low for PWM interface, setting to 40 ms"); param_set(_p_activation_time, &(_activation_time)); } // Advertise critical publishers here, because we cannot advertise in interrupt context struct camera_trigger_s trigger = {}; _trigger_pub = orb_advertise(ORB_ID(camera_trigger), &trigger); }
void CameraTrigger::poll(void *arg) { CameraTrigger *trig = reinterpret_cast<CameraTrigger *>(arg); bool updated; orb_check(trig->_vcommand_sub, &updated); if (updated) { orb_copy(ORB_ID(vehicle_command), trig->_vcommand_sub, &trig->_command); if(trig->_command.command == vehicle_command_s::VEHICLE_CMD_DO_TRIGGER_CONTROL) { if(trig->_command.param1 < 1) { if(trig->_trigger_enabled) { trig->_trigger_enabled = false ; } } else if(trig->_command.param1 >= 1) { if(!trig->_trigger_enabled) { trig->_trigger_enabled = true ; } } // Set trigger rate from command if(trig->_command.param2 > 0) { trig->_integration_time = trig->_command.param2; param_set(trig->integration_time, &(trig->_integration_time)); } } } if(!trig->_trigger_enabled) { hrt_call_after(&trig->_pollcall, 1e6, (hrt_callout)&CameraTrigger::poll, trig); return; } else { engage(trig); hrt_call_after(&trig->_firecall, trig->_activation_time*1000, (hrt_callout)&CameraTrigger::disengage, trig); orb_copy(ORB_ID(sensor_combined), trig->_sensor_sub, &trig->_sensor); trig->_trigger.timestamp = trig->_sensor.timestamp; // get IMU timestamp trig->_trigger.seq = trig->_trigger_seq++; if (trig->_trigger_pub != nullptr) { orb_publish(ORB_ID(camera_trigger), trig->_trigger_pub, &trig->_trigger); } else { trig->_trigger_pub = orb_advertise(ORB_ID(camera_trigger), &trig->_trigger); } hrt_call_after(&trig->_pollcall, (trig->_transfer_time + trig->_integration_time)*1000, (hrt_callout)&CameraTrigger::poll, trig); } }
static int multirotor_pos_control_thread_main(int argc, char *argv[]) { /* welcome user */ printf("[multirotor pos control] Control started, taking over position control\n"); /* structures */ struct vehicle_status_s state; struct vehicle_attitude_s att; //struct vehicle_global_position_setpoint_s global_pos_sp; struct vehicle_local_position_setpoint_s local_pos_sp; struct vehicle_vicon_position_s local_pos; struct manual_control_setpoint_s manual; struct vehicle_attitude_setpoint_s att_sp; /* subscribe to attitude, motor setpoints and system state */ int att_sub = orb_subscribe(ORB_ID(vehicle_attitude)); int state_sub = orb_subscribe(ORB_ID(vehicle_status)); int manual_sub = orb_subscribe(ORB_ID(manual_control_setpoint)); int local_pos_sub = orb_subscribe(ORB_ID(vehicle_vicon_position)); //int global_pos_sp_sub = orb_subscribe(ORB_ID(vehicle_global_position_setpoint)); int local_pos_sp_sub = orb_subscribe(ORB_ID(vehicle_local_position_setpoint)); /* publish attitude setpoint */ orb_advert_t att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &att_sp); thread_running = true; int loopcounter = 0; struct multirotor_position_control_params p; struct multirotor_position_control_param_handles h; parameters_init(&h); parameters_update(&h, &p); while (1) { /* get a local copy of the vehicle state */ orb_copy(ORB_ID(vehicle_status), state_sub, &state); /* get a local copy of manual setpoint */ orb_copy(ORB_ID(manual_control_setpoint), manual_sub, &manual); /* get a local copy of attitude */ orb_copy(ORB_ID(vehicle_attitude), att_sub, &att); /* get a local copy of local position */ orb_copy(ORB_ID(vehicle_vicon_position), local_pos_sub, &local_pos); /* get a local copy of local position setpoint */ orb_copy(ORB_ID(vehicle_local_position_setpoint), local_pos_sp_sub, &local_pos_sp); if (loopcounter == 500) { parameters_update(&h, &p); loopcounter = 0; } // if (state.state_machine == SYSTEM_STATE_AUTO) { // XXX IMPLEMENT POSITION CONTROL HERE float dT = 1.0f / 50.0f; float x_setpoint = 0.0f; // XXX enable switching between Vicon and local position estimate /* local pos is the Vicon position */ // XXX just an example, lacks rotation around world-body transformation att_sp.pitch_body = (local_pos.x - x_setpoint) * p.p; att_sp.roll_body = 0.0f; att_sp.yaw_body = 0.0f; att_sp.thrust = 0.3f; att_sp.timestamp = hrt_absolute_time(); /* publish new attitude setpoint */ orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp); // } else if (state.state_machine == SYSTEM_STATE_STABILIZED) { /* set setpoint to current position */ // XXX select pos reset channel on remote /* reset setpoint to current position (position hold) */ // if (1 == 2) { // 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; // } // } /* run at approximately 50 Hz */ usleep(20000); loopcounter++; } printf("[multirotor pos control] ending now...\n"); thread_running = false; fflush(stdout); return 0; }
static void handle_message(mavlink_message_t *msg) { if (msg->msgid == MAVLINK_MSG_ID_COMMAND_LONG) { mavlink_command_long_t cmd_mavlink; mavlink_msg_command_long_decode(msg, &cmd_mavlink); if (cmd_mavlink.target_system == mavlink_system.sysid && ((cmd_mavlink.target_component == mavlink_system.compid) || (cmd_mavlink.target_component == MAV_COMP_ID_ALL))) { //check for MAVLINK terminate command if (cmd_mavlink.command == MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN && ((int)cmd_mavlink.param1) == 3) { /* This is the link shutdown command, terminate mavlink */ printf("[mavlink] Terminating .. \n"); fflush(stdout); usleep(50000); /* terminate other threads and this thread */ thread_should_exit = true; } else { /* Copy the content of mavlink_command_long_t cmd_mavlink into command_t cmd */ vcmd.param1 = cmd_mavlink.param1; vcmd.param2 = cmd_mavlink.param2; vcmd.param3 = cmd_mavlink.param3; vcmd.param4 = cmd_mavlink.param4; vcmd.param5 = cmd_mavlink.param5; vcmd.param6 = cmd_mavlink.param6; vcmd.param7 = cmd_mavlink.param7; vcmd.command = cmd_mavlink.command; vcmd.target_system = cmd_mavlink.target_system; vcmd.target_component = cmd_mavlink.target_component; vcmd.source_system = msg->sysid; vcmd.source_component = msg->compid; vcmd.confirmation = cmd_mavlink.confirmation; /* check if topic is advertised */ if (cmd_pub <= 0) { cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd); } /* publish */ orb_publish(ORB_ID(vehicle_command), cmd_pub, &vcmd); } } } if (msg->msgid == MAVLINK_MSG_ID_OPTICAL_FLOW) { mavlink_optical_flow_t flow; mavlink_msg_optical_flow_decode(msg, &flow); struct optical_flow_s f; f.timestamp = hrt_absolute_time(); f.flow_raw_x = flow.flow_x; f.flow_raw_y = flow.flow_y; f.flow_comp_x_m = flow.flow_comp_m_x; f.flow_comp_y_m = flow.flow_comp_m_y; f.ground_distance_m = flow.ground_distance; f.quality = flow.quality; f.sensor_id = flow.sensor_id; /* check if topic is advertised */ if (flow_pub <= 0) { flow_pub = orb_advertise(ORB_ID(optical_flow), &f); } else { /* publish */ orb_publish(ORB_ID(optical_flow), flow_pub, &f); } } if (msg->msgid == MAVLINK_MSG_ID_SET_MODE) { /* Set mode on request */ mavlink_set_mode_t new_mode; mavlink_msg_set_mode_decode(msg, &new_mode); /* Copy the content of mavlink_command_long_t cmd_mavlink into command_t cmd */ vcmd.param1 = new_mode.base_mode; vcmd.param2 = new_mode.custom_mode; vcmd.param3 = 0; vcmd.param4 = 0; vcmd.param5 = 0; vcmd.param6 = 0; vcmd.param7 = 0; vcmd.command = MAV_CMD_DO_SET_MODE; vcmd.target_system = new_mode.target_system; vcmd.target_component = MAV_COMP_ID_ALL; vcmd.source_system = msg->sysid; vcmd.source_component = msg->compid; vcmd.confirmation = 1; /* check if topic is advertised */ if (cmd_pub <= 0) { cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd); } else { /* create command */ orb_publish(ORB_ID(vehicle_command), cmd_pub, &vcmd); } } /* Handle Vicon position estimates */ if (msg->msgid == MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE) { mavlink_vicon_position_estimate_t pos; mavlink_msg_vicon_position_estimate_decode(msg, &pos); vicon_position.x = pos.x; vicon_position.y = pos.y; vicon_position.z = pos.z; if (vicon_position_pub <= 0) { vicon_position_pub = orb_advertise(ORB_ID(vehicle_vicon_position), &vicon_position); } else { orb_publish(ORB_ID(vehicle_vicon_position), vicon_position_pub, &vicon_position); } } /* Handle quadrotor motor setpoints */ if (msg->msgid == MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST) { mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t quad_motors_setpoint; mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(msg, &quad_motors_setpoint); if (mavlink_system.sysid < 4) { /* switch to a receiving link mode */ gcs_link = false; /* * rate control mode - defined by MAVLink */ uint8_t ml_mode = 0; bool ml_armed = false; switch (quad_motors_setpoint.mode) { case 0: ml_armed = false; break; case 1: ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_RATES; ml_armed = true; break; case 2: ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE; ml_armed = true; break; case 3: ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY; break; case 4: ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_POSITION; break; } offboard_control_sp.p1 = (float)quad_motors_setpoint.roll[mavlink_system.sysid-1] / (float)INT16_MAX; offboard_control_sp.p2 = (float)quad_motors_setpoint.pitch[mavlink_system.sysid-1] / (float)INT16_MAX; offboard_control_sp.p3= (float)quad_motors_setpoint.yaw[mavlink_system.sysid-1] / (float)INT16_MAX; offboard_control_sp.p4 = (float)quad_motors_setpoint.thrust[mavlink_system.sysid-1]/(float)UINT16_MAX; if (quad_motors_setpoint.thrust[mavlink_system.sysid-1] == 0) { ml_armed = false; } offboard_control_sp.armed = ml_armed; offboard_control_sp.mode = ml_mode; offboard_control_sp.timestamp = hrt_absolute_time(); /* check if topic has to be advertised */ if (offboard_control_sp_pub <= 0) { offboard_control_sp_pub = orb_advertise(ORB_ID(offboard_control_setpoint), &offboard_control_sp); } else { /* Publish */ orb_publish(ORB_ID(offboard_control_setpoint), offboard_control_sp_pub, &offboard_control_sp); } } } }
void PX4FMU::task_main() { /* force a reset of the update rate */ _current_update_rate = 0; _armed_sub = orb_subscribe(ORB_ID(actuator_armed)); /* advertise the mixed control outputs */ actuator_outputs_s outputs; memset(&outputs, 0, sizeof(outputs)); #ifdef HRT_PPM_CHANNEL // rc input, published to ORB struct rc_input_values rc_in; orb_advert_t to_input_rc = 0; memset(&rc_in, 0, sizeof(rc_in)); rc_in.input_source = RC_INPUT_SOURCE_PX4FMU_PPM; #endif /* initialize PWM limit lib */ pwm_limit_init(&_pwm_limit); log("starting"); /* loop until killed */ while (!_task_should_exit) { if (_groups_subscribed != _groups_required) { subscribe(); _groups_subscribed = _groups_required; /* force setting update rate */ _current_update_rate = 0; } /* * Adjust actuator topic update rate to keep up with * the highest servo update rate configured. * * We always mix at max rate; some channels may update slower. */ unsigned max_rate = (_pwm_default_rate > _pwm_alt_rate) ? _pwm_default_rate : _pwm_alt_rate; if (_current_update_rate != max_rate) { _current_update_rate = max_rate; int update_rate_in_ms = int(1000 / _current_update_rate); /* reject faster than 500 Hz updates */ if (update_rate_in_ms < 2) { update_rate_in_ms = 2; } /* reject slower than 10 Hz updates */ if (update_rate_in_ms > 100) { update_rate_in_ms = 100; } debug("adjusted actuator update interval to %ums", update_rate_in_ms); for (unsigned i = 0; i < NUM_ACTUATOR_CONTROL_GROUPS; i++) { if (_control_subs[i] > 0) { orb_set_interval(_control_subs[i], update_rate_in_ms); } } // set to current max rate, even if we are actually checking slower/faster _current_update_rate = max_rate; } /* sleep waiting for data, stopping to check for PPM * input at 50Hz */ int ret = ::poll(_poll_fds, _poll_fds_num, CONTROL_INPUT_DROP_LIMIT_MS); /* this would be bad... */ if (ret < 0) { log("poll error %d", errno); continue; } else if (ret == 0) { /* timeout: no control data, switch to failsafe values */ // warnx("no PWM: failsafe"); } else { /* get controls for required topics */ unsigned poll_id = 0; for (unsigned i = 0; i < NUM_ACTUATOR_CONTROL_GROUPS; i++) { if (_control_subs[i] > 0) { if (_poll_fds[poll_id].revents & POLLIN) { orb_copy(_control_topics[i], _control_subs[i], &_controls[i]); } poll_id++; } } /* can we mix? */ if (_mixers != nullptr) { unsigned num_outputs; switch (_mode) { case MODE_2PWM: num_outputs = 2; break; case MODE_4PWM: num_outputs = 4; break; case MODE_6PWM: num_outputs = 6; break; case MODE_8PWM: num_outputs = 8; break; default: num_outputs = 0; break; } /* do mixing */ outputs.noutputs = _mixers->mix(&outputs.output[0], num_outputs); outputs.timestamp = hrt_absolute_time(); /* iterate actuators */ for (unsigned i = 0; i < num_outputs; i++) { /* last resort: catch NaN and INF */ if ((i >= outputs.noutputs) || !isfinite(outputs.output[i])) { /* * Value is NaN, INF or out of band - set to the minimum value. * This will be clearly visible on the servo status and will limit the risk of accidentally * spinning motors. It would be deadly in flight. */ outputs.output[i] = -1.0f; } } uint16_t pwm_limited[num_outputs]; /* the PWM limit call takes care of out of band errors and constrains */ pwm_limit_calc(_servo_armed, num_outputs, _disarmed_pwm, _min_pwm, _max_pwm, outputs.output, pwm_limited, &_pwm_limit); /* output to the servos */ for (unsigned i = 0; i < num_outputs; i++) { up_pwm_servo_set(i, pwm_limited[i]); } /* publish mixed control outputs */ if (_outputs_pub < 0) { _outputs_pub = orb_advertise(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1), &outputs); } else { orb_publish(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1), _outputs_pub, &outputs); } } } /* check arming state */ bool updated = false; orb_check(_armed_sub, &updated); if (updated) { orb_copy(ORB_ID(actuator_armed), _armed_sub, &_armed); /* update the armed status and check that we're not locked down */ bool set_armed = _armed.armed && !_armed.lockdown; if (_servo_armed != set_armed) _servo_armed = set_armed; /* update PWM status if armed or if disarmed PWM values are set */ bool pwm_on = (_armed.armed || _num_disarmed_set > 0); if (_pwm_on != pwm_on) { _pwm_on = pwm_on; up_pwm_servo_arm(pwm_on); } } #ifdef HRT_PPM_CHANNEL // see if we have new PPM input data if (ppm_last_valid_decode != rc_in.timestamp_last_signal) { // we have a new PPM frame. Publish it. rc_in.channel_count = ppm_decoded_channels; if (rc_in.channel_count > RC_INPUT_MAX_CHANNELS) { rc_in.channel_count = RC_INPUT_MAX_CHANNELS; } for (uint8_t i = 0; i < rc_in.channel_count; i++) { rc_in.values[i] = ppm_buffer[i]; } rc_in.timestamp_publication = ppm_last_valid_decode; rc_in.timestamp_last_signal = ppm_last_valid_decode; rc_in.rc_ppm_frame_length = ppm_frame_length; rc_in.rssi = RC_INPUT_RSSI_MAX; rc_in.rc_failsafe = false; rc_in.rc_lost = false; rc_in.rc_lost_frame_count = 0; rc_in.rc_total_frame_count = 0; /* lazily advertise on first publication */ if (to_input_rc == 0) { to_input_rc = orb_advertise(ORB_ID(input_rc), &rc_in); } else { orb_publish(ORB_ID(input_rc), to_input_rc, &rc_in); } } #endif } for (unsigned i = 0; i < NUM_ACTUATOR_CONTROL_GROUPS; i++) { if (_control_subs[i] > 0) { ::close(_control_subs[i]); _control_subs[i] = -1; } } ::close(_armed_sub); /* make sure servos are off */ up_pwm_servo_deinit(); log("stopping"); /* note - someone else is responsible for restoring the GPIO config */ /* tell the dtor that we are exiting */ _task = -1; _exit(0); }
void Navigator::task_main() { bool have_geofence_position_data = false; /* Try to load the geofence: * if /fs/microsd/etc/geofence.txt load from this file */ struct stat buffer; if (stat(GEOFENCE_FILENAME, &buffer) == 0) { PX4_INFO("Loading geofence from %s", GEOFENCE_FILENAME); _geofence.loadFromFile(GEOFENCE_FILENAME); } /* do subscriptions */ _global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position)); _local_pos_sub = orb_subscribe(ORB_ID(vehicle_local_position)); _gps_pos_sub = orb_subscribe(ORB_ID(vehicle_gps_position)); _sensor_combined_sub = orb_subscribe(ORB_ID(sensor_combined)); _fw_pos_ctrl_status_sub = orb_subscribe(ORB_ID(fw_pos_ctrl_status)); _vstatus_sub = orb_subscribe(ORB_ID(vehicle_status)); _land_detected_sub = orb_subscribe(ORB_ID(vehicle_land_detected)); _home_pos_sub = orb_subscribe(ORB_ID(home_position)); _onboard_mission_sub = orb_subscribe(ORB_ID(onboard_mission)); _offboard_mission_sub = orb_subscribe(ORB_ID(offboard_mission)); _param_update_sub = orb_subscribe(ORB_ID(parameter_update)); _vehicle_command_sub = orb_subscribe(ORB_ID(vehicle_command)); _traffic_sub = orb_subscribe(ORB_ID(transponder_report)); /* copy all topics first time */ vehicle_status_update(); vehicle_land_detected_update(); global_position_update(); local_position_update(); gps_position_update(); sensor_combined_update(); home_position_update(true); fw_pos_ctrl_status_update(true); params_update(); /* wakeup source(s) */ px4_pollfd_struct_t fds[1] = {}; /* Setup of loop */ fds[0].fd = _local_pos_sub; fds[0].events = POLLIN; /* rate-limit position subscription to 20 Hz / 50 ms */ orb_set_interval(_local_pos_sub, 50); while (!_task_should_exit) { /* wait for up to 1000ms for data */ int pret = px4_poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 1000); if (pret == 0) { /* Let the loop run anyway, don't do `continue` here. */ } else if (pret < 0) { /* this is undesirable but not much we can do - might want to flag unhappy status */ PX4_ERR("poll error %d, %d", pret, errno); usleep(10000); continue; } else { if (fds[0].revents & POLLIN) { /* success, local pos is available */ local_position_update(); } } perf_begin(_loop_perf); bool updated; /* gps updated */ orb_check(_gps_pos_sub, &updated); if (updated) { gps_position_update(); if (_geofence.getSource() == Geofence::GF_SOURCE_GPS) { have_geofence_position_data = true; } } /* global position updated */ orb_check(_global_pos_sub, &updated); if (updated) { global_position_update(); if (_geofence.getSource() == Geofence::GF_SOURCE_GLOBALPOS) { have_geofence_position_data = true; } } /* sensors combined updated */ orb_check(_sensor_combined_sub, &updated); if (updated) { sensor_combined_update(); } /* parameters updated */ orb_check(_param_update_sub, &updated); if (updated) { params_update(); } /* vehicle status updated */ orb_check(_vstatus_sub, &updated); if (updated) { vehicle_status_update(); } /* vehicle land detected updated */ orb_check(_land_detected_sub, &updated); if (updated) { vehicle_land_detected_update(); } /* navigation capabilities updated */ orb_check(_fw_pos_ctrl_status_sub, &updated); if (updated) { fw_pos_ctrl_status_update(); } /* home position updated */ orb_check(_home_pos_sub, &updated); if (updated) { home_position_update(); } /* vehicle_command updated */ orb_check(_vehicle_command_sub, &updated); if (updated) { vehicle_command_s cmd; orb_copy(ORB_ID(vehicle_command), _vehicle_command_sub, &cmd); if (cmd.command == vehicle_command_s::VEHICLE_CMD_DO_GO_AROUND) { // DO_GO_AROUND is currently handled by the position controller (unacknowledged) // TODO: move DO_GO_AROUND handling to navigator publish_vehicle_command_ack(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED); } else if (cmd.command == vehicle_command_s::VEHICLE_CMD_DO_REPOSITION) { position_setpoint_triplet_s *rep = get_reposition_triplet(); position_setpoint_triplet_s *curr = get_position_setpoint_triplet(); // store current position as previous position and goal as next rep->previous.yaw = get_global_position()->yaw; rep->previous.lat = get_global_position()->lat; rep->previous.lon = get_global_position()->lon; rep->previous.alt = get_global_position()->alt; rep->current.loiter_radius = get_loiter_radius(); rep->current.loiter_direction = 1; rep->current.type = position_setpoint_s::SETPOINT_TYPE_LOITER; rep->current.cruising_speed = get_cruising_speed(); rep->current.cruising_throttle = get_cruising_throttle(); // Go on and check which changes had been requested if (PX4_ISFINITE(cmd.param4)) { rep->current.yaw = cmd.param4; } else { rep->current.yaw = NAN; } if (PX4_ISFINITE(cmd.param5) && PX4_ISFINITE(cmd.param6)) { // Position change with optional altitude change rep->current.lat = (cmd.param5 < 1000) ? cmd.param5 : cmd.param5 / (double)1e7; rep->current.lon = (cmd.param6 < 1000) ? cmd.param6 : cmd.param6 / (double)1e7; if (PX4_ISFINITE(cmd.param7)) { rep->current.alt = cmd.param7; } else { rep->current.alt = get_global_position()->alt; } } else if (PX4_ISFINITE(cmd.param7) && curr->current.valid && PX4_ISFINITE(curr->current.lat) && PX4_ISFINITE(curr->current.lon)) { // Altitude without position change rep->current.lat = curr->current.lat; rep->current.lon = curr->current.lon; rep->current.alt = cmd.param7; } else { // All three set to NaN - hold in current position rep->current.lat = get_global_position()->lat; rep->current.lon = get_global_position()->lon; rep->current.alt = get_global_position()->alt; } rep->previous.valid = true; rep->current.valid = true; rep->next.valid = false; // CMD_DO_REPOSITION is acknowledged by commander } else if (cmd.command == vehicle_command_s::VEHICLE_CMD_NAV_TAKEOFF) { position_setpoint_triplet_s *rep = get_takeoff_triplet(); // store current position as previous position and goal as next rep->previous.yaw = get_global_position()->yaw; rep->previous.lat = get_global_position()->lat; rep->previous.lon = get_global_position()->lon; rep->previous.alt = get_global_position()->alt; rep->current.loiter_radius = get_loiter_radius(); rep->current.loiter_direction = 1; rep->current.type = position_setpoint_s::SETPOINT_TYPE_TAKEOFF; if (home_position_valid()) { rep->current.yaw = cmd.param4; rep->previous.valid = true; } else { rep->current.yaw = get_local_position()->yaw; rep->previous.valid = false; } if (PX4_ISFINITE(cmd.param5) && PX4_ISFINITE(cmd.param6)) { rep->current.lat = (cmd.param5 < 1000) ? cmd.param5 : cmd.param5 / (double)1e7; rep->current.lon = (cmd.param6 < 1000) ? cmd.param6 : cmd.param6 / (double)1e7; } else { // If one of them is non-finite, reset both rep->current.lat = NAN; rep->current.lon = NAN; } rep->current.alt = cmd.param7; rep->current.valid = true; rep->next.valid = false; // CMD_NAV_TAKEOFF is acknowledged by commander } else if (cmd.command == vehicle_command_s::VEHICLE_CMD_DO_LAND_START) { /* find NAV_CMD_DO_LAND_START in the mission and * use MAV_CMD_MISSION_START to start the mission there */ int land_start = _mission.find_offboard_land_start(); if (land_start != -1) { vehicle_command_s vcmd = {}; vcmd.command = vehicle_command_s::VEHICLE_CMD_MISSION_START; vcmd.param1 = land_start; publish_vehicle_cmd(&vcmd); } else { PX4_WARN("planned landing not available"); } publish_vehicle_command_ack(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED); } else if (cmd.command == vehicle_command_s::VEHICLE_CMD_MISSION_START) { if (get_mission_result()->valid && PX4_ISFINITE(cmd.param1) && (cmd.param1 >= 0) && (cmd.param1 < _mission_result.seq_total)) { _mission.set_current_offboard_mission_index(cmd.param1); } // CMD_MISSION_START is acknowledged by commander } else if (cmd.command == vehicle_command_s::VEHICLE_CMD_DO_CHANGE_SPEED) { if (cmd.param2 > FLT_EPSILON) { // XXX not differentiating ground and airspeed yet set_cruising_speed(cmd.param2); } else { set_cruising_speed(); /* if no speed target was given try to set throttle */ if (cmd.param3 > FLT_EPSILON) { set_cruising_throttle(cmd.param3 / 100); } else { set_cruising_throttle(); } } // TODO: handle responses for supported DO_CHANGE_SPEED options? publish_vehicle_command_ack(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED); } else if (cmd.command == vehicle_command_s::VEHICLE_CMD_DO_SET_ROI || cmd.command == vehicle_command_s::VEHICLE_CMD_NAV_ROI) { _vroi = {}; _vroi.mode = cmd.param1; switch (_vroi.mode) { case vehicle_command_s::VEHICLE_ROI_NONE: break; case vehicle_command_s::VEHICLE_ROI_WPNEXT: // TODO: implement point toward next MISSION break; case vehicle_command_s::VEHICLE_ROI_WPINDEX: _vroi.mission_seq = cmd.param2; break; case vehicle_command_s::VEHICLE_ROI_LOCATION: _vroi.lat = cmd.param5; _vroi.lon = cmd.param6; _vroi.alt = cmd.param7; break; case vehicle_command_s::VEHICLE_ROI_TARGET: _vroi.target_seq = cmd.param2; break; default: _vroi.mode = vehicle_command_s::VEHICLE_ROI_NONE; break; } _vroi.timestamp = hrt_absolute_time(); if (_vehicle_roi_pub != nullptr) { orb_publish(ORB_ID(vehicle_roi), _vehicle_roi_pub, &_vroi); } else { _vehicle_roi_pub = orb_advertise(ORB_ID(vehicle_roi), &_vroi); } publish_vehicle_command_ack(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED); } } /* Check for traffic */ check_traffic(); /* Check geofence violation */ static hrt_abstime last_geofence_check = 0; if (have_geofence_position_data && (_geofence.getGeofenceAction() != geofence_result_s::GF_ACTION_NONE) && (hrt_elapsed_time(&last_geofence_check) > GEOFENCE_CHECK_INTERVAL)) { bool inside = _geofence.check(_global_pos, _gps_pos, _sensor_combined.baro_alt_meter, _home_pos, home_position_valid()); last_geofence_check = hrt_absolute_time(); have_geofence_position_data = false; _geofence_result.timestamp = hrt_absolute_time(); _geofence_result.geofence_action = _geofence.getGeofenceAction(); _geofence_result.home_required = _geofence.isHomeRequired(); if (!inside) { /* inform other apps via the mission result */ _geofence_result.geofence_violated = true; /* Issue a warning about the geofence violation once */ if (!_geofence_violation_warning_sent) { mavlink_log_critical(&_mavlink_log_pub, "Geofence violation"); _geofence_violation_warning_sent = true; } } else { /* inform other apps via the mission result */ _geofence_result.geofence_violated = false; /* Reset the _geofence_violation_warning_sent field */ _geofence_violation_warning_sent = false; } publish_geofence_result(); } /* Do stuff according to navigation state set by commander */ NavigatorMode *navigation_mode_new{nullptr}; switch (_vstatus.nav_state) { case vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION: _pos_sp_triplet_published_invalid_once = false; navigation_mode_new = &_mission; break; case vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER: _pos_sp_triplet_published_invalid_once = false; navigation_mode_new = &_loiter; break; case vehicle_status_s::NAVIGATION_STATE_AUTO_RCRECOVER: _pos_sp_triplet_published_invalid_once = false; navigation_mode_new = &_rcLoss; break; case vehicle_status_s::NAVIGATION_STATE_AUTO_RTL: _pos_sp_triplet_published_invalid_once = false; navigation_mode_new = &_rtl; break; case vehicle_status_s::NAVIGATION_STATE_AUTO_TAKEOFF: _pos_sp_triplet_published_invalid_once = false; navigation_mode_new = &_takeoff; break; case vehicle_status_s::NAVIGATION_STATE_AUTO_LAND: _pos_sp_triplet_published_invalid_once = false; navigation_mode_new = &_land; break; case vehicle_status_s::NAVIGATION_STATE_DESCEND: _pos_sp_triplet_published_invalid_once = false; navigation_mode_new = &_land; break; case vehicle_status_s::NAVIGATION_STATE_AUTO_RTGS: _pos_sp_triplet_published_invalid_once = false; navigation_mode_new = &_dataLinkLoss; break; case vehicle_status_s::NAVIGATION_STATE_AUTO_LANDENGFAIL: _pos_sp_triplet_published_invalid_once = false; navigation_mode_new = &_engineFailure; break; case vehicle_status_s::NAVIGATION_STATE_AUTO_LANDGPSFAIL: _pos_sp_triplet_published_invalid_once = false; navigation_mode_new = &_gpsFailure; break; case vehicle_status_s::NAVIGATION_STATE_AUTO_FOLLOW_TARGET: _pos_sp_triplet_published_invalid_once = false; navigation_mode_new = &_follow_target; break; case vehicle_status_s::NAVIGATION_STATE_MANUAL: case vehicle_status_s::NAVIGATION_STATE_ACRO: case vehicle_status_s::NAVIGATION_STATE_ALTCTL: case vehicle_status_s::NAVIGATION_STATE_POSCTL: case vehicle_status_s::NAVIGATION_STATE_TERMINATION: case vehicle_status_s::NAVIGATION_STATE_OFFBOARD: case vehicle_status_s::NAVIGATION_STATE_STAB: default: _pos_sp_triplet_published_invalid_once = false; navigation_mode_new = nullptr; _can_loiter_at_sp = false; break; } /* we have a new navigation mode: reset triplet */ if (_navigation_mode != navigation_mode_new) { reset_triplets(); } _navigation_mode = navigation_mode_new; /* iterate through navigation modes and set active/inactive for each */ for (unsigned int i = 0; i < NAVIGATOR_MODE_ARRAY_SIZE; i++) { _navigation_mode_array[i]->run(_navigation_mode == _navigation_mode_array[i]); } /* if we landed and have not received takeoff setpoint then stay in idle */ if (_land_detected.landed && !((_vstatus.nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_TAKEOFF) || (_vstatus.nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION))) { _pos_sp_triplet.current.type = position_setpoint_s::SETPOINT_TYPE_IDLE; _pos_sp_triplet.current.valid = true; _pos_sp_triplet.previous.valid = false; _pos_sp_triplet.next.valid = false; } /* if nothing is running, set position setpoint triplet invalid once */ if (_navigation_mode == nullptr && !_pos_sp_triplet_published_invalid_once) { _pos_sp_triplet_published_invalid_once = true; reset_triplets(); } if (_pos_sp_triplet_updated) { _pos_sp_triplet.timestamp = hrt_absolute_time(); publish_position_setpoint_triplet(); _pos_sp_triplet_updated = false; } if (_mission_result_updated) { publish_mission_result(); _mission_result_updated = false; } perf_end(_loop_perf); } orb_unsubscribe(_global_pos_sub); orb_unsubscribe(_local_pos_sub); orb_unsubscribe(_gps_pos_sub); orb_unsubscribe(_sensor_combined_sub); orb_unsubscribe(_fw_pos_ctrl_status_sub); orb_unsubscribe(_vstatus_sub); orb_unsubscribe(_land_detected_sub); orb_unsubscribe(_home_pos_sub); orb_unsubscribe(_onboard_mission_sub); orb_unsubscribe(_offboard_mission_sub); orb_unsubscribe(_param_update_sub); orb_unsubscribe(_vehicle_command_sub); PX4_INFO("exiting"); _navigator_task = -1; }
int FixedwingEstimator::check_filter_state() { /* * CHECK IF THE INPUT DATA IS SANE */ struct ekf_status_report ekf_report; int check = _ekf->CheckAndBound(&ekf_report); const char* ekfname = "att pos estimator: "; switch (check) { case 0: /* all ok */ break; case 1: { const char* str = "NaN in states, resetting"; warnx("%s", str); mavlink_log_critical(_mavlink_fd, "%s%s", ekfname, str); break; } case 2: { const char* str = "stale IMU data, resetting"; warnx("%s", str); mavlink_log_critical(_mavlink_fd, "%s%s", ekfname, str); break; } case 3: { const char* str = "switching to dynamic state"; warnx("%s", str); mavlink_log_info(_mavlink_fd, "%s%s", ekfname, str); break; } case 4: { const char* str = "excessive gyro offsets"; warnx("%s", str); mavlink_log_info(_mavlink_fd, "%s%s", ekfname, str); break; } case 5: { const char* str = "GPS velocity divergence"; warnx("%s", str); mavlink_log_info(_mavlink_fd, "%s%s", ekfname, str); break; } case 6: { const char* str = "excessive covariances"; warnx("%s", str); mavlink_log_info(_mavlink_fd, "%s%s", ekfname, str); break; } default: { const char* str = "unknown reset condition"; warnx("%s", str); mavlink_log_critical(_mavlink_fd, "%s%s", ekfname, str); } } struct estimator_status_report rep; memset(&rep, 0, sizeof(rep)); // If error flag is set, we got a filter reset if (check && ekf_report.error) { // Count the reset condition perf_count(_perf_reset); } else if (_ekf_logging) { _ekf->GetFilterState(&ekf_report); } if (_ekf_logging || check) { rep.timestamp = hrt_absolute_time(); rep.nan_flags |= (((uint8_t)ekf_report.angNaN) << 0); rep.nan_flags |= (((uint8_t)ekf_report.summedDelVelNaN) << 1); rep.nan_flags |= (((uint8_t)ekf_report.KHNaN) << 2); rep.nan_flags |= (((uint8_t)ekf_report.KHPNaN) << 3); rep.nan_flags |= (((uint8_t)ekf_report.PNaN) << 4); rep.nan_flags |= (((uint8_t)ekf_report.covarianceNaN) << 5); rep.nan_flags |= (((uint8_t)ekf_report.kalmanGainsNaN) << 6); rep.nan_flags |= (((uint8_t)ekf_report.statesNaN) << 7); rep.health_flags |= (((uint8_t)ekf_report.velHealth) << 0); rep.health_flags |= (((uint8_t)ekf_report.posHealth) << 1); rep.health_flags |= (((uint8_t)ekf_report.hgtHealth) << 2); rep.health_flags |= (((uint8_t)!ekf_report.gyroOffsetsExcessive) << 3); rep.timeout_flags |= (((uint8_t)ekf_report.velTimeout) << 0); rep.timeout_flags |= (((uint8_t)ekf_report.posTimeout) << 1); rep.timeout_flags |= (((uint8_t)ekf_report.hgtTimeout) << 2); rep.timeout_flags |= (((uint8_t)ekf_report.imuTimeout) << 3); if (_debug > 10) { if (rep.health_flags < ((1 << 0) | (1 << 1) | (1 << 2) | (1 << 3))) { warnx("health: VEL:%s POS:%s HGT:%s OFFS:%s", ((rep.health_flags & (1 << 0)) ? "OK" : "ERR"), ((rep.health_flags & (1 << 1)) ? "OK" : "ERR"), ((rep.health_flags & (1 << 2)) ? "OK" : "ERR"), ((rep.health_flags & (1 << 3)) ? "OK" : "ERR")); } if (rep.timeout_flags) { warnx("timeout: %s%s%s%s", ((rep.timeout_flags & (1 << 0)) ? "VEL " : ""), ((rep.timeout_flags & (1 << 1)) ? "POS " : ""), ((rep.timeout_flags & (1 << 2)) ? "HGT " : ""), ((rep.timeout_flags & (1 << 3)) ? "IMU " : "")); } } // Copy all states or at least all that we can fit unsigned ekf_n_states = ekf_report.n_states; unsigned max_states = (sizeof(rep.states) / sizeof(rep.states[0])); rep.n_states = (ekf_n_states < max_states) ? ekf_n_states : max_states; for (unsigned i = 0; i < rep.n_states; i++) { rep.states[i] = ekf_report.states[i]; } for (unsigned i = 0; i < rep.n_states; i++) { rep.states[i] = ekf_report.states[i]; } if (_estimator_status_pub > 0) { orb_publish(ORB_ID(estimator_status), _estimator_status_pub, &rep); } else { _estimator_status_pub = orb_advertise(ORB_ID(estimator_status), &rep); } } return check; }
int flow_position_estimator_thread_main(int argc, char *argv[]) { /* welcome user */ thread_running = true; printf("[flow position estimator] starting\n"); /* rotation matrix for transformation of optical flow speed vectors */ static const int8_t rotM_flow_sensor[3][3] = {{ 0, -1, 0 }, { 1, 0, 0 }, { 0, 0, 1 }}; // 90deg rotated const float time_scale = powf(10.0f,-6.0f); static float speed[3] = {0.0f, 0.0f, 0.0f}; static float flow_speed[3] = {0.0f, 0.0f, 0.0f}; static float global_speed[3] = {0.0f, 0.0f, 0.0f}; static uint32_t counter = 0; static uint64_t time_last_flow = 0; // in ms static float dt = 0.0f; // seconds static float sonar_last = 0.0f; static bool sonar_valid = false; static float sonar_lp = 0.0f; /* subscribe to vehicle status, attitude, sensors and flow*/ struct actuator_armed_s armed; memset(&armed, 0, sizeof(armed)); struct vehicle_control_mode_s control_mode; memset(&control_mode, 0, sizeof(control_mode)); struct vehicle_attitude_s att; memset(&att, 0, sizeof(att)); struct vehicle_attitude_setpoint_s att_sp; memset(&att_sp, 0, sizeof(att_sp)); struct optical_flow_s flow; memset(&flow, 0, sizeof(flow)); /* subscribe to parameter changes */ int parameter_update_sub = orb_subscribe(ORB_ID(parameter_update)); /* subscribe to armed topic */ int armed_sub = orb_subscribe(ORB_ID(actuator_armed)); /* subscribe to safety topic */ int control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode)); /* subscribe to attitude */ int vehicle_attitude_sub = orb_subscribe(ORB_ID(vehicle_attitude)); /* subscribe to attitude setpoint */ int vehicle_attitude_setpoint_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint)); /* subscribe to optical flow*/ int optical_flow_sub = orb_subscribe(ORB_ID(optical_flow)); /* init local position and filtered flow struct */ struct vehicle_local_position_s local_pos = { .x = 0.0f, .y = 0.0f, .z = 0.0f, .vx = 0.0f, .vy = 0.0f, .vz = 0.0f }; struct filtered_bottom_flow_s filtered_flow = { .sumx = 0.0f, .sumy = 0.0f, .vx = 0.0f, .vy = 0.0f }; /* advert pub messages */ orb_advert_t local_pos_pub = orb_advertise(ORB_ID(vehicle_local_position), &local_pos); orb_advert_t filtered_flow_pub = orb_advertise(ORB_ID(filtered_bottom_flow), &filtered_flow); /* vehicle flying status parameters */ bool vehicle_liftoff = false; bool sensors_ready = false; /* parameters init*/ struct flow_position_estimator_params params; struct flow_position_estimator_param_handles param_handles; parameters_init(¶m_handles); parameters_update(¶m_handles, ¶ms); perf_counter_t mc_loop_perf = perf_alloc(PC_ELAPSED, "flow_position_estimator_runtime"); perf_counter_t mc_interval_perf = perf_alloc(PC_INTERVAL, "flow_position_estimator_interval"); perf_counter_t mc_err_perf = perf_alloc(PC_COUNT, "flow_position_estimator_err"); while (!thread_should_exit) { if (sensors_ready) { /*This runs at the rate of the sensors */ struct pollfd fds[2] = { { .fd = optical_flow_sub, .events = POLLIN }, { .fd = parameter_update_sub, .events = POLLIN } }; /* wait for a sensor update, check for exit condition every 500 ms */ int ret = poll(fds, 2, 500); if (ret < 0) { /* poll error, count it in perf */ perf_count(mc_err_perf); } else if (ret == 0) { /* no return value, ignore */ // printf("[flow position estimator] no bottom flow.\n"); } else { /* parameter update available? */ if (fds[1].revents & POLLIN) { /* read from param to clear updated flag */ struct parameter_update_s update; orb_copy(ORB_ID(parameter_update), parameter_update_sub, &update); parameters_update(¶m_handles, ¶ms); printf("[flow position estimator] parameters updated.\n"); } /* only if flow data changed */ if (fds[0].revents & POLLIN) { perf_begin(mc_loop_perf); orb_copy(ORB_ID(optical_flow), optical_flow_sub, &flow); /* got flow, updating attitude and status as well */ orb_copy(ORB_ID(vehicle_attitude), vehicle_attitude_sub, &att); orb_copy(ORB_ID(vehicle_attitude_setpoint), vehicle_attitude_setpoint_sub, &att_sp); orb_copy(ORB_ID(actuator_armed), armed_sub, &armed); orb_copy(ORB_ID(vehicle_control_mode), control_mode_sub, &control_mode); /* vehicle state estimation */ float sonar_new = flow.ground_distance_m; /* set liftoff boolean * -> at bottom sonar sometimes does not work correctly, and has to be calibrated (distance higher than 0.3m) * -> accept sonar measurements after reaching calibration distance (values between 0.3m and 1.0m for some time) * -> minimum sonar value 0.3m */ if (!vehicle_liftoff) { if (armed.armed && att_sp.thrust > params.minimum_liftoff_thrust && sonar_new > 0.3f && sonar_new < 1.0f) vehicle_liftoff = true; } else { if (!armed.armed || (att_sp.thrust < params.minimum_liftoff_thrust && sonar_new <= 0.3f)) vehicle_liftoff = false; } /* calc dt between flow timestamps */ /* ignore first flow msg */ if(time_last_flow == 0) { time_last_flow = flow.timestamp; continue; } dt = (float)(flow.timestamp - time_last_flow) * time_scale ; time_last_flow = flow.timestamp; /* only make position update if vehicle is lift off or DEBUG is activated*/ if (vehicle_liftoff || params.debug) { /* copy flow */ flow_speed[0] = flow.flow_comp_x_m; flow_speed[1] = flow.flow_comp_y_m; flow_speed[2] = 0.0f; /* convert to bodyframe velocity */ for(uint8_t i = 0; i < 3; i++) { float sum = 0.0f; for(uint8_t j = 0; j < 3; j++) sum = sum + flow_speed[j] * rotM_flow_sensor[j][i]; speed[i] = sum; } /* update filtered flow */ filtered_flow.sumx = filtered_flow.sumx + speed[0] * dt; filtered_flow.sumy = filtered_flow.sumy + speed[1] * dt; filtered_flow.vx = speed[0]; filtered_flow.vy = speed[1]; // TODO add yaw rotation correction (with distance to vehicle zero) /* convert to globalframe velocity * -> local position is currently not used for position control */ for(uint8_t i = 0; i < 3; i++) { float sum = 0.0f; for(uint8_t j = 0; j < 3; j++) sum = sum + speed[j] * att.R[i][j]; global_speed[i] = sum; } local_pos.x = local_pos.x + global_speed[0] * dt; local_pos.y = local_pos.y + global_speed[1] * dt; local_pos.vx = global_speed[0]; local_pos.vy = global_speed[1]; } else { /* set speed to zero and let position as it is */ filtered_flow.vx = 0; filtered_flow.vy = 0; local_pos.vx = 0; local_pos.vy = 0; } /* filtering ground distance */ if (!vehicle_liftoff || !armed.armed) { /* not possible to fly */ sonar_valid = false; local_pos.z = 0.0f; } else { sonar_valid = true; } if (sonar_valid || params.debug) { /* simple lowpass sonar filtering */ /* if new value or with sonar update frequency */ if (sonar_new != sonar_last || counter % 10 == 0) { sonar_lp = 0.05f * sonar_new + 0.95f * sonar_lp; sonar_last = sonar_new; } float height_diff = sonar_new - sonar_lp; /* if over 1/2m spike follow lowpass */ if (height_diff < -params.sonar_lower_lp_threshold || height_diff > params.sonar_upper_lp_threshold) { local_pos.z = -sonar_lp; } else { local_pos.z = -sonar_new; } } filtered_flow.timestamp = hrt_absolute_time(); local_pos.timestamp = hrt_absolute_time(); /* publish local position */ if(isfinite(local_pos.x) && isfinite(local_pos.y) && isfinite(local_pos.z) && isfinite(local_pos.vx) && isfinite(local_pos.vy)) { orb_publish(ORB_ID(vehicle_local_position), local_pos_pub, &local_pos); } /* publish filtered flow */ if(isfinite(filtered_flow.sumx) && isfinite(filtered_flow.sumy) && isfinite(filtered_flow.vx) && isfinite(filtered_flow.vy)) { orb_publish(ORB_ID(filtered_bottom_flow), filtered_flow_pub, &filtered_flow); } /* measure in what intervals the position estimator runs */ perf_count(mc_interval_perf); perf_end(mc_loop_perf); } } } else { /* sensors not ready waiting for first attitude msg */ /* polling */ struct pollfd fds[1] = { { .fd = vehicle_attitude_sub, .events = POLLIN }, }; /* wait for a attitude message, check for exit condition every 5 s */ int ret = poll(fds, 1, 5000); if (ret < 0) { /* poll error, count it in perf */ perf_count(mc_err_perf); } else if (ret == 0) { /* no return value, ignore */ printf("[flow position estimator] no attitude received.\n"); } else { if (fds[0].revents & POLLIN){ sensors_ready = true; printf("[flow position estimator] initialized.\n"); } } }
/**************************************************************************** * main ****************************************************************************/ int position_estimator_inav_thread_main(int argc, char *argv[]) { warnx("started"); int mavlink_fd; mavlink_fd = open(MAVLINK_LOG_DEVICE, 0); mavlink_log_info(mavlink_fd, "[inav] started"); float x_est[3] = { 0.0f, 0.0f, 0.0f }; float y_est[3] = { 0.0f, 0.0f, 0.0f }; float z_est[3] = { 0.0f, 0.0f, 0.0f }; int baro_init_cnt = 0; int baro_init_num = 200; float baro_offset = 0.0f; // baro offset for reference altitude, initialized on start, then adjusted float surface_offset = 0.0f; // ground level offset from reference altitude float surface_offset_rate = 0.0f; // surface offset change rate float alt_avg = 0.0f; bool landed = true; hrt_abstime landed_time = 0; hrt_abstime accel_timestamp = 0; hrt_abstime baro_timestamp = 0; bool ref_inited = false; hrt_abstime ref_init_start = 0; const hrt_abstime ref_init_delay = 1000000; // wait for 1s after 3D fix uint16_t accel_updates = 0; uint16_t baro_updates = 0; uint16_t gps_updates = 0; uint16_t attitude_updates = 0; uint16_t flow_updates = 0; hrt_abstime updates_counter_start = hrt_absolute_time(); hrt_abstime pub_last = hrt_absolute_time(); hrt_abstime t_prev = 0; /* acceleration in NED frame */ float accel_NED[3] = { 0.0f, 0.0f, -CONSTANTS_ONE_G }; /* store error when sensor updates, but correct on each time step to avoid jumps in estimated value */ float corr_acc[] = { 0.0f, 0.0f, 0.0f }; // N E D float acc_bias[] = { 0.0f, 0.0f, 0.0f }; // body frame float corr_baro = 0.0f; // D float corr_gps[3][2] = { { 0.0f, 0.0f }, // N (pos, vel) { 0.0f, 0.0f }, // E (pos, vel) { 0.0f, 0.0f }, // D (pos, vel) }; float w_gps_xy = 1.0f; float w_gps_z = 1.0f; float corr_sonar = 0.0f; float corr_sonar_filtered = 0.0f; float corr_flow[] = { 0.0f, 0.0f }; // N E float w_flow = 0.0f; float sonar_prev = 0.0f; hrt_abstime sonar_time = 0; // time of last sonar measurement (not filtered) hrt_abstime sonar_valid_time = 0; // time of last sonar measurement used for correction (filtered) hrt_abstime xy_src_time = 0; // time of last available position data bool gps_valid = false; // GPS is valid bool sonar_valid = false; // sonar is valid bool flow_valid = false; // flow is valid bool flow_accurate = false; // flow should be accurate (this flag not updated if flow_valid == false) /* declare and safely initialize all structs */ struct actuator_controls_s actuator; memset(&actuator, 0, sizeof(actuator)); struct actuator_armed_s armed; memset(&armed, 0, sizeof(armed)); struct sensor_combined_s sensor; memset(&sensor, 0, sizeof(sensor)); struct vehicle_gps_position_s gps; memset(&gps, 0, sizeof(gps)); struct vehicle_attitude_s att; memset(&att, 0, sizeof(att)); struct vehicle_local_position_s local_pos; memset(&local_pos, 0, sizeof(local_pos)); struct optical_flow_s flow; memset(&flow, 0, sizeof(flow)); struct vehicle_global_position_s global_pos; memset(&global_pos, 0, sizeof(global_pos)); /* subscribe */ int parameter_update_sub = orb_subscribe(ORB_ID(parameter_update)); int actuator_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS); int armed_sub = orb_subscribe(ORB_ID(actuator_armed)); int sensor_combined_sub = orb_subscribe(ORB_ID(sensor_combined)); int vehicle_attitude_sub = orb_subscribe(ORB_ID(vehicle_attitude)); int optical_flow_sub = orb_subscribe(ORB_ID(optical_flow)); int vehicle_gps_position_sub = orb_subscribe(ORB_ID(vehicle_gps_position)); /* advertise */ orb_advert_t vehicle_local_position_pub = orb_advertise(ORB_ID(vehicle_local_position), &local_pos); orb_advert_t vehicle_global_position_pub = orb_advertise(ORB_ID(vehicle_global_position), &global_pos); struct position_estimator_inav_params params; struct position_estimator_inav_param_handles pos_inav_param_handles; /* initialize parameter handles */ parameters_init(&pos_inav_param_handles); /* first parameters read at start up */ struct parameter_update_s param_update; orb_copy(ORB_ID(parameter_update), parameter_update_sub, ¶m_update); /* read from param topic to clear updated flag */ /* first parameters update */ parameters_update(&pos_inav_param_handles, ¶ms); struct pollfd fds_init[1] = { { .fd = sensor_combined_sub, .events = POLLIN }, };
/* Main Thread */ int fixedwing_control_thread_main(int argc, char *argv[]) { /* read arguments */ bool verbose = false; for (int i = 1; i < argc; i++) { if (strcmp(argv[i], "-v") == 0 || strcmp(argv[i], "--verbose") == 0) { verbose = true; } } /* welcome user (warnx prints a line, including an appended\n, with variable arguments */ warnx("[example fixedwing control] started"); /* initialize parameters, first the handles, then the values */ parameters_init(&ph); parameters_update(&ph, &p); /* * PX4 uses a publish/subscribe design pattern to enable * multi-threaded communication. * * The most elegant aspect of this is that controllers and * other processes can either 'react' to new data, or run * at their own pace. * * PX4 developer guide: * https://pixhawk.ethz.ch/px4/dev/shared_object_communication * * Wikipedia description: * http://en.wikipedia.org/wiki/Publish–subscribe_pattern * */ /* * Declare and safely initialize all structs to zero. * * These structs contain the system state and things * like attitude, position, the current waypoint, etc. */ struct vehicle_attitude_s att; memset(&att, 0, sizeof(att)); struct vehicle_attitude_setpoint_s att_sp; memset(&att_sp, 0, sizeof(att_sp)); struct vehicle_rates_setpoint_s rates_sp; memset(&rates_sp, 0, sizeof(rates_sp)); struct vehicle_global_position_s global_pos; memset(&global_pos, 0, sizeof(global_pos)); struct manual_control_setpoint_s manual_sp; memset(&manual_sp, 0, sizeof(manual_sp)); struct vehicle_status_s vstatus; memset(&vstatus, 0, sizeof(vstatus)); struct position_setpoint_s global_sp; memset(&global_sp, 0, sizeof(global_sp)); /* output structs - this is what is sent to the mixer */ struct actuator_controls_s actuators; memset(&actuators, 0, sizeof(actuators)); /* publish actuator controls with zero values */ for (unsigned i = 0; i < actuator_controls_s::NUM_ACTUATOR_CONTROLS; i++) { actuators.control[i] = 0.0f; } /* * Advertise that this controller will publish actuator * control values and the rate setpoint */ orb_advert_t actuator_pub = orb_advertise(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, &actuators); orb_advert_t rates_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &rates_sp); /* subscribe to topics. */ int att_sub = orb_subscribe(ORB_ID(vehicle_attitude)); int global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position)); int manual_sp_sub = orb_subscribe(ORB_ID(manual_control_setpoint)); int vstatus_sub = orb_subscribe(ORB_ID(vehicle_status)); int global_sp_sub = orb_subscribe(ORB_ID(position_setpoint_triplet)); int param_sub = orb_subscribe(ORB_ID(parameter_update)); /* Setup of loop */ struct pollfd fds[2] = {}; fds[0].fd = param_sub; fds[0].events = POLLIN; fds[1].fd = att_sub; fds[1].events = POLLIN; while (!thread_should_exit) { /* * Wait for a sensor or param update, check for exit condition every 500 ms. * This means that the execution will block here without consuming any resources, * but will continue to execute the very moment a new attitude measurement or * a param update is published. So no latency in contrast to the polling * design pattern (do not confuse the poll() system call with polling). * * This design pattern makes the controller also agnostic of the attitude * update speed - it runs as fast as the attitude updates with minimal latency. */ int ret = poll(fds, 2, 500); if (ret < 0) { /* * Poll error, this will not really happen in practice, * but its good design practice to make output an error message. */ warnx("poll error"); } else if (ret == 0) { /* no return value = nothing changed for 500 ms, ignore */ } else { /* only update parameters if they changed */ if (fds[0].revents & POLLIN) { /* read from param to clear updated flag (uORB API requirement) */ struct parameter_update_s update; orb_copy(ORB_ID(parameter_update), param_sub, &update); /* if a param update occured, re-read our parameters */ parameters_update(&ph, &p); } /* only run controller if attitude changed */ if (fds[1].revents & POLLIN) { /* Check if there is a new position measurement or position setpoint */ bool pos_updated; orb_check(global_pos_sub, &pos_updated); bool global_sp_updated; orb_check(global_sp_sub, &global_sp_updated); bool manual_sp_updated; orb_check(manual_sp_sub, &manual_sp_updated); /* get a local copy of attitude */ orb_copy(ORB_ID(vehicle_attitude), att_sub, &att); if (global_sp_updated) { struct position_setpoint_triplet_s triplet; orb_copy(ORB_ID(position_setpoint_triplet), global_sp_sub, &triplet); memcpy(&global_sp, &triplet.current, sizeof(global_sp)); } if (manual_sp_updated) /* get the RC (or otherwise user based) input */ { orb_copy(ORB_ID(manual_control_setpoint), manual_sp_sub, &manual_sp); } /* check if the throttle was ever more than 50% - go later only to failsafe if yes */ if (PX4_ISFINITE(manual_sp.z) && (manual_sp.z >= 0.6f) && (manual_sp.z <= 1.0f)) { } /* get the system status and the flight mode we're in */ orb_copy(ORB_ID(vehicle_status), vstatus_sub, &vstatus); /* publish rates */ orb_publish(ORB_ID(vehicle_rates_setpoint), rates_pub, &rates_sp); /* sanity check and publish actuator outputs */ if (PX4_ISFINITE(actuators.control[0]) && PX4_ISFINITE(actuators.control[1]) && PX4_ISFINITE(actuators.control[2]) && PX4_ISFINITE(actuators.control[3])) { orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators); if (verbose) { warnx("published"); } } } } } printf("[ex_fixedwing_control] exiting, stopping all motors.\n"); thread_running = false; /* kill all outputs */ for (unsigned i = 0; i < actuator_controls_s::NUM_ACTUATOR_CONTROLS; i++) { actuators.control[i] = 0.0f; } orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators); fflush(stdout); return 0; }
void task_main(int argc, char *argv[]) { _is_running = true; if (uart_initialize(_device) < 0) { PX4_ERR("Failed to initialize UART."); return; } // Subscribe for orb topics _controls_sub = orb_subscribe(ORB_ID(actuator_controls_0)); _armed_sub = orb_subscribe(ORB_ID(actuator_armed)); // Start disarmed _armed.armed = false; _armed.prearmed = false; // Set up poll topic px4_pollfd_struct_t fds[1]; fds[0].fd = _controls_sub; fds[0].events = POLLIN; /* Don't limit poll intervall for now, 250 Hz should be fine. */ //orb_set_interval(_controls_sub, 10); // Set up mixer if (initialize_mixer(MIXER_FILENAME) < 0) { PX4_ERR("Mixer initialization failed."); return; } pwm_limit_init(&_pwm_limit); // TODO XXX: this is needed otherwise we crash in the callback context. _rc_pub = orb_advertise(ORB_ID(input_rc), &_rc); // Main loop while (!_task_should_exit) { int pret = px4_poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 10); /* Timed out, do a periodic check for _task_should_exit. */ if (pret == 0) { continue; } /* This is undesirable but not much we can do. */ if (pret < 0) { PX4_WARN("poll error %d, %d", pret, errno); /* sleep a bit before next try */ usleep(100000); continue; } if (fds[0].revents & POLLIN) { orb_copy(ORB_ID(actuator_controls_0), _controls_sub, &_controls); _outputs.timestamp = _controls.timestamp; /* do mixing */ _outputs.noutputs = _mixer->mix(_outputs.output, 0 /* not used */, NULL); /* disable unused ports by setting their output to NaN */ for (size_t i = _outputs.noutputs; i < sizeof(_outputs.output) / sizeof(_outputs.output[0]); i++) { _outputs.output[i] = NAN; } const uint16_t reverse_mask = 0; uint16_t disarmed_pwm[4]; uint16_t min_pwm[4]; uint16_t max_pwm[4]; for (unsigned int i = 0; i < 4; i++) { disarmed_pwm[i] = _pwm_disarmed; min_pwm[i] = _pwm_min; max_pwm[i] = _pwm_max; } uint16_t pwm[4]; // TODO FIXME: pre-armed seems broken pwm_limit_calc(_armed.armed, false/*_armed.prearmed*/, _outputs.noutputs, reverse_mask, disarmed_pwm, min_pwm, max_pwm, _outputs.output, pwm, &_pwm_limit); send_outputs_mavlink(pwm, 4); if (_outputs_pub != nullptr) { orb_publish(ORB_ID(actuator_outputs), _outputs_pub, &_outputs); } else { _outputs_pub = orb_advertise(ORB_ID(actuator_outputs), &_outputs); } } bool updated; orb_check(_armed_sub, &updated); if (updated) { orb_copy(ORB_ID(actuator_armed), _armed_sub, &_armed); } } uart_deinitialize(); orb_unsubscribe(_controls_sub); orb_unsubscribe(_armed_sub); _is_running = false; }
/* * EKF Attitude Estimator main function. * * Estimates the attitude recursively once started. * * @param argc number of commandline arguments (plus command name) * @param argv strings containing the arguments */ void app_att_est_ekf_main(void* parameter) { const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds float dt = 0.005f; /* state vector x has the following entries [ax,ay,az||mx,my,mz||wox,woy,woz||wx,wy,wz]' */ float z_k[9] = {0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 9.81f, 0.2f, -0.2f, 0.2f}; /**< Measurement vector */ float x_aposteriori_k[12]; /**< states */ float P_aposteriori_k[144] = {100.f, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 100.f, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 100.f, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 100.f, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 100.f, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 100.f, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 100.f, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 100.f, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 100.f, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.0f, 100.0f, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.0f, 0, 100.0f, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.0f, 0, 0, 100.0f, }; /**< init: diagonal matrix with big values */ float x_aposteriori[12]; float P_aposteriori[144]; /* output euler angles */ float euler[3] = {0.0f, 0.0f, 0.0f}; float Rot_matrix[9] = {1.f, 0, 0, 0, 1.f, 0, 0, 0, 1.f }; /**< init: identity matrix */ // print text printf("Extended Kalman Filter Attitude Estimator initialized..\n\n"); fflush(stdout); int overloadcounter = 19; /* Initialize filter */ attitudeKalmanfilter_initialize(); /* store start time to guard against too slow update rates */ uint64_t last_run = hrt_absolute_time(); sensor_combined_s raw; rt_memset(&raw, 0, sizeof(raw)); //struct vehicle_gps_position_s gps; //rt_memset(&gps, 0, sizeof(gps)); //struct vehicle_global_position_s global_pos; //rt_memset(&global_pos, 0, sizeof(global_pos)); vehicle_attitude_s att; rt_memset(&att, 0, sizeof(att)); //struct vehicle_control_mode_s control_mode; //rt_memset(&control_mode, 0, sizeof(control_mode)); uint64_t last_data = 0; uint64_t last_measurement = 0; rt_uint32_t sensors_sub = 0; uint64_t last_timestamp_acc = 0; uint64_t last_timestamp_gyro = 0; uint64_t last_timestamp_mag = 0; /* rotation matrix */ float R[3][3] = {1,0,0, 0,1,0, 0,0,1}; /* subscribe to raw data */ orb_subscribe(ORB_ID(sensor_combined),&sensors_sub); orb_advertise(ORB_ID(vehicle_attitude), &att); att_est_ekf_running = true; bool initialized = false; /* magnetic declination, in radians */ float mag_decl = 0.0f; /* rotation matrix for magnetic declination */ float R_mag[3][3] = {1,0,0, 0,1,0, 0,0,1}; uint8_t update_vect[3] = {0, 0, 0}; rt_memset(&ekf_params, 0, sizeof(ekf_params)); ekf_params.q[0] = 1e-4f; ekf_params.q[1] = 0.08f; ekf_params.q[2] = 0.009f; ekf_params.q[3] = 0.005f; ekf_params.q[4] = 0.0f; ekf_params.r[0] = 0.0008f; ekf_params.r[1] = 10000.0f; ekf_params.r[2] = 100.0f; ekf_params.r[3] = 0.0f; /* Main loop*/ while (!att_est_ekf_should_exit) { /* only run filter if sensor values changed */ if (orb_check(&sensors_sub,5000) == RT_EOK) { /* get latest measurements */ orb_copy(ORB_ID(sensor_combined), &raw); } else{ rt_kprintf("sensors data lost!\n"); } if (!initialized) { initialized = true; } else { /* Calculate data time difference in seconds */ dt = (raw.acc_timestamp - last_measurement) / 1000000.0f; last_measurement = raw.acc_timestamp; if(raw.gyro_timestamp != last_timestamp_gyro) { update_vect[0] = 1; last_timestamp_gyro = raw.gyro_timestamp; } if(raw.acc_timestamp != last_timestamp_acc) { update_vect[1] = 1; last_timestamp_acc = raw.acc_timestamp; } if(raw.mag_timestamp != last_timestamp_mag) { update_vect[2] = 1; last_timestamp_mag = raw.mag_timestamp; } z_k[0] = raw.gyro_rad_s[0]; z_k[1] = raw.gyro_rad_s[1]; z_k[2] = raw.gyro_rad_s[2]; z_k[3] = raw.acc_m_s2[0]; z_k[4] = raw.acc_m_s2[1]; z_k[5] = raw.acc_m_s2[2]; z_k[6] = raw.mag_ga[0]; z_k[7] = raw.mag_ga[1]; z_k[8] = raw.mag_ga[2]; uint64_t now = hrt_absolute_time(); unsigned int time_elapsed = now - last_run; last_run = now; if (time_elapsed > loop_interval_alarm) { /* cpu overload */ overloadcounter++; } static bool const_initialized = false; /* initialize with good values once we have a reasonable dt estimate */ if (!const_initialized && dt < 0.05f && dt > 0.001f) { dt = 0.005f; /* update mag declination rotation matrix */ euler_to_rot_mat(R_mag,0.0f, 0.0f, mag_decl); x_aposteriori_k[0] = z_k[0]; x_aposteriori_k[1] = z_k[1]; x_aposteriori_k[2] = z_k[2]; x_aposteriori_k[3] = 0.0f; x_aposteriori_k[4] = 0.0f; x_aposteriori_k[5] = 0.0f; x_aposteriori_k[6] = z_k[3]; x_aposteriori_k[7] = z_k[4]; x_aposteriori_k[8] = z_k[5]; x_aposteriori_k[9] = z_k[6]; x_aposteriori_k[10] = z_k[7]; x_aposteriori_k[11] = z_k[8]; const_initialized = true; } /* do not execute the filter if not initialized */ if (!const_initialized) { continue; } attitudeKalmanfilter(update_vect, dt, z_k, x_aposteriori_k, P_aposteriori_k, ekf_params.q, ekf_params.r, euler, Rot_matrix, x_aposteriori, P_aposteriori); for(int i = 0;i < 3;i++) { update_vect[i] = 0; } /* swap values for next iteration, check for fatal inputs */ if (isfinite(euler[0]) && isfinite(euler[1]) && isfinite(euler[2])) { rt_memcpy(P_aposteriori_k, P_aposteriori, sizeof(P_aposteriori_k)); rt_memcpy(x_aposteriori_k, x_aposteriori, sizeof(x_aposteriori_k)); } else { /* due to inputs or numerical failure the output is invalid, skip it */ continue; } if (last_data > 0 && raw.acc_timestamp - last_data > 30000) printf("[attitude estimator ekf] sensor data missed! (%llu)\n", raw.acc_timestamp - last_data); last_data = raw.acc_timestamp; /* send out */ att.timestamp = raw.acc_timestamp; att.roll = euler[0]; att.pitch = euler[1]; att.yaw = euler[2] + mag_decl; att.rollspeed = x_aposteriori[0]; att.pitchspeed = x_aposteriori[1]; att.yawspeed = x_aposteriori[2]; att.rollacc = x_aposteriori[3]; att.pitchacc = x_aposteriori[4]; att.yawacc = x_aposteriori[5]; att.g_comp[0] = raw.acc_m_s2[0]; att.g_comp[1] = raw.acc_m_s2[1]; att.g_comp[2] = raw.acc_m_s2[2]; /* copy offsets */ rt_memcpy(&att.rate_offsets, &(x_aposteriori[3]), sizeof(att.rate_offsets)); /* magnetic declination */ float R_body[3][3] = {0}; rt_memcpy(&R_body, &Rot_matrix, sizeof(R_body)); //R = R_mag * R_body; for(int i = 0;i < 3;i++){ for(int j = 0;j < 3;i++) { R[i][j] = 0; for(int k = 0;k < 3;k++) R[i][j] += R_mag[i][k] * R_body[k][j]; } } /* copy rotation matrix */ rt_memcpy(&att.R, &R, sizeof(att.R)); att.R_valid = true; if (isfinite(att.roll) && isfinite(att.pitch) && isfinite(att.yaw)) { // Broadcast orb_publish(ORB_ID(vehicle_attitude), &att); } else { rt_kprintf("NaN in roll/pitch/yaw estimate!"); } } } att_est_ekf_running = false; }
static int mpc_thread_main(int argc, char *argv[]) { /* welcome user */ printf("[multirotor pos control] Control started, taking over position control\n"); /* structures */ struct vehicle_status_s state; struct vehicle_attitude_s att; //struct vehicle_global_position_setpoint_s global_pos_sp; struct vehicle_local_position_setpoint_s local_pos_sp; struct vehicle_local_position_s local_pos; struct manual_control_setpoint_s manual; struct vehicle_attitude_setpoint_s att_sp; /* subscribe to attitude, motor setpoints and system state */ int att_sub = orb_subscribe(ORB_ID(vehicle_attitude)); int state_sub = orb_subscribe(ORB_ID(vehicle_status)); int manual_sub = orb_subscribe(ORB_ID(manual_control_setpoint)); int local_pos_sub = orb_subscribe(ORB_ID(vehicle_local_position)); //int global_pos_sp_sub = orb_subscribe(ORB_ID(vehicle_global_position_setpoint)); int local_pos_sp_sub = orb_subscribe(ORB_ID(vehicle_local_position_setpoint)); /* publish attitude setpoint */ orb_advert_t att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &att_sp); while (1) { /* get a local copy of the vehicle state */ orb_copy(ORB_ID(vehicle_status), state_sub, &state); /* get a local copy of manual setpoint */ orb_copy(ORB_ID(manual_control_setpoint), manual_sub, &manual); /* get a local copy of attitude */ orb_copy(ORB_ID(vehicle_attitude), att_sub, &att); /* get a local copy of local position */ orb_copy(ORB_ID(vehicle_local_position), local_pos_sub, &local_pos); /* get a local copy of local position setpoint */ orb_copy(ORB_ID(vehicle_local_position_setpoint), local_pos_sp_sub, &local_pos_sp); if (state.state_machine == SYSTEM_STATE_AUTO) { position_control(&state, &manual, &att, &local_pos, &local_pos_sp, &att_sp); /* publish new attitude setpoint */ orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp); } else if (state.state_machine == SYSTEM_STATE_STABILIZE) { /* set setpoint to current position */ // XXX select pos reset channel on remote /* reset setpoint to current position (position hold) */ // if (1 == 2) { // 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; // } } /* run at approximately 50 Hz */ usleep(20000); counter++; } /* close uarts */ close(ardrone_write); ar_multiplexing_deinit(gpios); printf("[multirotor pos control] ending now...\r\n"); fflush(stdout); return 0; }
int HMC5883::collect() { #pragma pack(push, 1) struct { /* status register and data as read back from the device */ uint8_t x[2]; uint8_t z[2]; uint8_t y[2]; } hmc_report; #pragma pack(pop) struct { int16_t x, y, z; } report; int ret; uint8_t cmd; uint8_t check_counter; perf_begin(_sample_perf); struct mag_report new_report; /* this should be fairly close to the end of the measurement, so the best approximation of the time */ new_report.timestamp = hrt_absolute_time(); new_report.error_count = perf_event_count(_comms_errors); /* * @note We could read the status register here, which could tell us that * we were too early and that the output registers are still being * written. In the common case that would just slow us down, and * we're better off just never being early. */ /* get measurements from the device */ cmd = ADDR_DATA_OUT_X_MSB; ret = transfer(&cmd, 1, (uint8_t *)&hmc_report, sizeof(hmc_report)); if (ret != OK) { perf_count(_comms_errors); debug("data/status read error"); goto out; } /* swap the data we just received */ report.x = (((int16_t)hmc_report.x[0]) << 8) + hmc_report.x[1]; report.y = (((int16_t)hmc_report.y[0]) << 8) + hmc_report.y[1]; report.z = (((int16_t)hmc_report.z[0]) << 8) + hmc_report.z[1]; /* * If any of the values are -4096, there was an internal math error in the sensor. * Generalise this to a simple range check that will also catch some bit errors. */ if ((abs(report.x) > 2048) || (abs(report.y) > 2048) || (abs(report.z) > 2048)) { perf_count(_comms_errors); goto out; } /* * RAW outputs * * to align the sensor axes with the board, x and y need to be flipped * and y needs to be negated */ new_report.x_raw = report.y; new_report.y_raw = -report.x; /* z remains z */ new_report.z_raw = report.z; /* scale values for output */ #ifdef PX4_I2C_BUS_ONBOARD if (_bus == PX4_I2C_BUS_ONBOARD) { // convert onboard so it matches offboard for the // scaling below report.y = -report.y; report.x = -report.x; } #endif /* the standard external mag by 3DR has x pointing to the * right, y pointing backwards, and z down, therefore switch x * and y and invert y */ new_report.x = ((-report.y * _range_scale) - _scale.x_offset) * _scale.x_scale; /* flip axes and negate value for y */ new_report.y = ((report.x * _range_scale) - _scale.y_offset) * _scale.y_scale; /* z remains z */ new_report.z = ((report.z * _range_scale) - _scale.z_offset) * _scale.z_scale; // apply user specified rotation rotate_3f(_rotation, new_report.x, new_report.y, new_report.z); if (!(_pub_blocked)) { if (_mag_topic != -1) { /* publish it */ orb_publish(_mag_orb_id, _mag_topic, &new_report); } else { _mag_topic = orb_advertise(_mag_orb_id, &new_report); if (_mag_topic < 0) debug("ADVERT FAIL"); } } _last_report = new_report; /* post a report to the ring */ if (_reports->force(&new_report)) { perf_count(_buffer_overflows); } /* notify anyone waiting for data */ poll_notify(POLLIN); /* periodically check the range register and configuration registers. With a bad I2C cable it is possible for the registers to become corrupt, leading to bad readings. It doesn't happen often, but given the poor cables some vehicles have it is worth checking for. */ check_counter = perf_event_count(_sample_perf) % 256; if (check_counter == 0) { check_range(); } if (check_counter == 128) { check_conf(); } ret = OK; out: perf_end(_sample_perf); return ret; }
void VtolAttitudeControl::task_main() { fflush(stdout); /* do subscriptions */ _v_att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint)); _mc_virtual_att_sp_sub = orb_subscribe(ORB_ID(mc_virtual_attitude_setpoint)); _fw_virtual_att_sp_sub = orb_subscribe(ORB_ID(fw_virtual_attitude_setpoint)); _mc_virtual_v_rates_sp_sub = orb_subscribe(ORB_ID(mc_virtual_rates_setpoint)); _fw_virtual_v_rates_sp_sub = orb_subscribe(ORB_ID(fw_virtual_rates_setpoint)); _v_att_sub = orb_subscribe(ORB_ID(vehicle_attitude)); _v_att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint)); _v_control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode)); _params_sub = orb_subscribe(ORB_ID(parameter_update)); _manual_control_sp_sub = orb_subscribe(ORB_ID(manual_control_setpoint)); _armed_sub = orb_subscribe(ORB_ID(actuator_armed)); _local_pos_sub = orb_subscribe(ORB_ID(vehicle_local_position)); _airspeed_sub = orb_subscribe(ORB_ID(airspeed)); _battery_status_sub = orb_subscribe(ORB_ID(battery_status)); _vehicle_cmd_sub = orb_subscribe(ORB_ID(vehicle_command)); _tecs_status_sub = orb_subscribe(ORB_ID(tecs_status)); _land_detected_sub = orb_subscribe(ORB_ID(vehicle_land_detected)); _actuator_inputs_mc = orb_subscribe(ORB_ID(actuator_controls_virtual_mc)); _actuator_inputs_fw = orb_subscribe(ORB_ID(actuator_controls_virtual_fw)); parameters_update(); // initialize parameter cache /* update vtol vehicle status*/ _vtol_vehicle_status.fw_permanent_stab = _params.vtol_fw_permanent_stab == 1 ? true : false; // make sure we start with idle in mc mode _vtol_type->set_idle_mc(); /* wakeup source*/ px4_pollfd_struct_t fds[3] = {}; /*input_mc, input_fw, parameters*/ fds[0].fd = _actuator_inputs_mc; fds[0].events = POLLIN; fds[1].fd = _actuator_inputs_fw; fds[1].events = POLLIN; fds[2].fd = _params_sub; fds[2].events = POLLIN; while (!_task_should_exit) { /*Advertise/Publish vtol vehicle status*/ _vtol_vehicle_status.timestamp = hrt_absolute_time(); if (_vtol_vehicle_status_pub != nullptr) { orb_publish(ORB_ID(vtol_vehicle_status), _vtol_vehicle_status_pub, &_vtol_vehicle_status); } else { _vtol_vehicle_status_pub = orb_advertise(ORB_ID(vtol_vehicle_status), &_vtol_vehicle_status); } /* wait for up to 100ms for data */ int pret = px4_poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100); /* timed out - periodic check for _task_should_exit */ if (pret == 0) { continue; } /* this is undesirable but not much we can do - might want to flag unhappy status */ if (pret < 0) { warn("poll error %d, %d", pret, errno); /* sleep a bit before next try */ usleep(100000); continue; } if (fds[2].revents & POLLIN) { //parameters were updated, read them now /* read from param to clear updated flag */ struct parameter_update_s update; orb_copy(ORB_ID(parameter_update), _params_sub, &update); /* update parameters from storage */ parameters_update(); } _vtol_vehicle_status.fw_permanent_stab = _params.vtol_fw_permanent_stab == 1 ? true : false; mc_virtual_att_sp_poll(); fw_virtual_att_sp_poll(); vehicle_control_mode_poll(); //Check for changes in vehicle control mode. vehicle_manual_poll(); //Check for changes in manual inputs. arming_status_poll(); //Check for arming status updates. vehicle_attitude_setpoint_poll();//Check for changes in attitude set points vehicle_attitude_poll(); //Check for changes in attitude actuator_controls_mc_poll(); //Check for changes in mc_attitude_control output actuator_controls_fw_poll(); //Check for changes in fw_attitude_control output vehicle_rates_sp_mc_poll(); vehicle_rates_sp_fw_poll(); parameters_update_poll(); vehicle_local_pos_poll(); // Check for new sensor values vehicle_airspeed_poll(); vehicle_battery_poll(); vehicle_cmd_poll(); tecs_status_poll(); land_detected_poll(); // update the vtol state machine which decides which mode we are in _vtol_type->update_vtol_state(); // reset transition command if not auto control if (_v_control_mode.flag_control_manual_enabled) { if (_vtol_type->get_mode() == ROTARY_WING) { _transition_command = vtol_vehicle_status_s::VEHICLE_VTOL_STATE_MC; } else if (_vtol_type->get_mode() == FIXED_WING) { _transition_command = vtol_vehicle_status_s::VEHICLE_VTOL_STATE_FW; } else if (_vtol_type->get_mode() == TRANSITION_TO_MC) { /* We want to make sure that a mode change (manual>auto) during the back transition * doesn't result in an unsafe state. This prevents the instant fall back to * fixed-wing on the switch from manual to auto */ _transition_command = vtol_vehicle_status_s::VEHICLE_VTOL_STATE_MC; } } // check in which mode we are in and call mode specific functions if (_vtol_type->get_mode() == ROTARY_WING) { // vehicle is in rotary wing mode _vtol_vehicle_status.vtol_in_rw_mode = true; _vtol_vehicle_status.vtol_in_trans_mode = false; // got data from mc attitude controller if (fds[0].revents & POLLIN) { orb_copy(ORB_ID(actuator_controls_virtual_mc), _actuator_inputs_mc, &_actuators_mc_in); _vtol_type->update_mc_state(); fill_mc_att_rates_sp(); } } else if (_vtol_type->get_mode() == FIXED_WING) { // vehicle is in fw mode _vtol_vehicle_status.vtol_in_rw_mode = false; _vtol_vehicle_status.vtol_in_trans_mode = false; // got data from fw attitude controller if (fds[1].revents & POLLIN) { orb_copy(ORB_ID(actuator_controls_virtual_fw), _actuator_inputs_fw, &_actuators_fw_in); vehicle_manual_poll(); _vtol_type->update_fw_state(); fill_fw_att_rates_sp(); } } else if (_vtol_type->get_mode() == TRANSITION_TO_MC || _vtol_type->get_mode() == TRANSITION_TO_FW) { // vehicle is doing a transition _vtol_vehicle_status.vtol_in_trans_mode = true; _vtol_vehicle_status.vtol_in_rw_mode = true; //making mc attitude controller work during transition _vtol_vehicle_status.in_transition_to_fw = (_vtol_type->get_mode() == TRANSITION_TO_FW); bool got_new_data = false; if (fds[0].revents & POLLIN) { orb_copy(ORB_ID(actuator_controls_virtual_mc), _actuator_inputs_mc, &_actuators_mc_in); got_new_data = true; } if (fds[1].revents & POLLIN) { orb_copy(ORB_ID(actuator_controls_virtual_fw), _actuator_inputs_fw, &_actuators_fw_in); got_new_data = true; } // update transition state if got any new data if (got_new_data) { _vtol_type->update_transition_state(); fill_mc_att_rates_sp(); publish_att_sp(); } } else if (_vtol_type->get_mode() == EXTERNAL) { // we are using external module to generate attitude/thrust setpoint _vtol_type->update_external_state(); } publish_att_sp(); _vtol_type->fill_actuator_outputs(); /* Only publish if the proper mode(s) are enabled */ if (_v_control_mode.flag_control_attitude_enabled || _v_control_mode.flag_control_rates_enabled || _v_control_mode.flag_control_manual_enabled) { if (_actuators_0_pub != nullptr) { orb_publish(ORB_ID(actuator_controls_0), _actuators_0_pub, &_actuators_out_0); } else { _actuators_0_pub = orb_advertise(ORB_ID(actuator_controls_0), &_actuators_out_0); } if (_actuators_1_pub != nullptr) { orb_publish(ORB_ID(actuator_controls_1), _actuators_1_pub, &_actuators_out_1); } else { _actuators_1_pub = orb_advertise(ORB_ID(actuator_controls_1), &_actuators_out_1); } } // publish the attitude rates setpoint if (_v_rates_sp_pub != nullptr) { orb_publish(ORB_ID(vehicle_rates_setpoint), _v_rates_sp_pub, &_v_rates_sp); } else { _v_rates_sp_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &_v_rates_sp); } } warnx("exit"); _control_task = -1; return; }
void Gimbal::cycle() { if (!_initialized) { /* get a subscription handle on the vehicle command topic */ _vehicle_command_sub = orb_subscribe(ORB_ID(vehicle_command)); /* get a publication handle on actuator output topic */ struct actuator_controls_s zero_report; memset(&zero_report, 0, sizeof(zero_report)); zero_report.timestamp = hrt_absolute_time(); _actuator_controls_2_topic = orb_advertise(ORB_ID(actuator_controls_2), &zero_report); if (_actuator_controls_2_topic == nullptr) { warnx("advert err"); } _initialized = true; } bool updated = false; perf_begin(_sample_perf); float roll = 0.0f; float pitch = 0.0f; float yaw = 0.0f; if (_att_sub < 0) { _att_sub = orb_subscribe(ORB_ID(vehicle_attitude)); } vehicle_attitude_s att; orb_copy(ORB_ID(vehicle_attitude), _att_sub, &att); if (_attitude_compensation_roll) { roll = 1.0f / M_PI_F * -att.roll; updated = true; } if (_attitude_compensation_pitch) { pitch = 1.0f / M_PI_F * -att.pitch; updated = true; } if (_attitude_compensation_yaw) { yaw = 1.0f / M_PI_F * att.yaw; updated = true; } struct vehicle_command_s cmd; bool cmd_updated; orb_check(_vehicle_command_sub, &cmd_updated); if (cmd_updated) { orb_copy(ORB_ID(vehicle_command), _vehicle_command_sub, &cmd); if (cmd.command == vehicle_command_s::VEHICLE_CMD_DO_MOUNT_CONTROL || cmd.command == vehicle_command_s::VEHICLE_CMD_DO_MOUNT_CONTROL_QUAT) { _control_cmd = cmd; _control_cmd_set = true; } else if (cmd.command == vehicle_command_s::VEHICLE_CMD_DO_MOUNT_CONFIGURE) { _config_cmd = cmd; _config_cmd_set = true; } } if (_config_cmd_set) { _config_cmd_set = false; _attitude_compensation_roll = (int)_config_cmd.param2 == 1; _attitude_compensation_pitch = (int)_config_cmd.param3 == 1; _attitude_compensation_yaw = (int)_config_cmd.param4 == 1; } if (_control_cmd_set) { unsigned mountMode = _control_cmd.param7; DEVICE_DEBUG("control_cmd: %d, mountMode %d | param1: %8.4f param2: %8.4f", _control_cmd.command, mountMode, (double)_control_cmd.param1, (double)_control_cmd.param2); if (_control_cmd.command == vehicle_command_s::VEHICLE_CMD_DO_MOUNT_CONTROL && mountMode == vehicle_command_s::VEHICLE_MOUNT_MODE_MAVLINK_TARGETING) { /* Convert to range -1 ... 1, which corresponds to -180deg ... 180deg */ roll += 1.0f / M_PI_F * M_DEG_TO_RAD_F * _control_cmd.param1; pitch += 1.0f / M_PI_F * M_DEG_TO_RAD_F * _control_cmd.param2; yaw += 1.0f / M_PI_F * M_DEG_TO_RAD_F * _control_cmd.param3; updated = true; } if (_control_cmd.command == vehicle_command_s::VEHICLE_CMD_DO_MOUNT_CONTROL_QUAT && mountMode == vehicle_command_s::VEHICLE_MOUNT_MODE_MAVLINK_TARGETING) { float gimbalDirectionQuat[] = {_control_cmd.param1, _control_cmd.param2, _control_cmd.param3, _control_cmd.param4}; math::Vector<3> gimablDirectionEuler = math::Quaternion(gimbalDirectionQuat).to_dcm().to_euler(); roll += gimablDirectionEuler(0); pitch += gimablDirectionEuler(1); yaw += gimablDirectionEuler(2); updated = true; } } if (updated) { struct actuator_controls_s controls; // DEVICE_DEBUG("publishing | roll: %8.4f pitch: %8.4f yaw: %8.4f", (double)roll, (double)pitch, (double)yaw); /* fill in the final control values */ controls.timestamp = hrt_absolute_time(); controls.control[0] = roll; controls.control[1] = pitch; controls.control[2] = yaw; /* publish it */ orb_publish(ORB_ID(actuator_controls_2), _actuator_controls_2_topic, &controls); } /* notify anyone waiting for data */ poll_notify(POLLIN); perf_end(_sample_perf); /* schedule a fresh cycle call when the measurement is done */ work_queue(LPWORK, &_work, (worker_t)&Gimbal::cycle_trampoline, this, USEC2TICK(GIMBAL_UPDATE_INTERVAL)); }
void PX4FMU::cycle() { if (!_initialized) { /* force a reset of the update rate */ _current_update_rate = 0; _armed_sub = orb_subscribe(ORB_ID(actuator_armed)); //_param_sub = orb_subscribe(ORB_ID(parameter_update)); /* initialize PWM limit lib */ pwm_limit_init(&_pwm_limit); update_pwm_rev_mask(); #ifdef RC_SERIAL_PORT _sbus_fd = sbus_init(RC_SERIAL_PORT, true); #endif _initialized = true; } if (_groups_subscribed != _groups_required) { subscribe(); _groups_subscribed = _groups_required; /* force setting update rate */ _current_update_rate = 0; } /* * Adjust actuator topic update rate to keep up with * the highest servo update rate configured. * * We always mix at max rate; some channels may update slower. */ unsigned max_rate = (_pwm_default_rate > _pwm_alt_rate) ? _pwm_default_rate : _pwm_alt_rate; if (_current_update_rate != max_rate) { _current_update_rate = max_rate; int update_rate_in_ms = int(1000 / _current_update_rate); /* reject faster than 500 Hz updates */ if (update_rate_in_ms < 2) { update_rate_in_ms = 2; } /* reject slower than 10 Hz updates */ if (update_rate_in_ms > 100) { update_rate_in_ms = 100; } //DEVICE_DEBUG("adjusted actuator update interval to %ums\n", update_rate_in_ms); for (unsigned i = 0; i < actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS; i++) { if (_control_subs[i] > 0) { orb_set_interval(_control_subs[i], update_rate_in_ms); } } // set to current max rate, even if we are actually checking slower/faster _current_update_rate = max_rate; } /* check if anything updated */ //从mkblctrl-blctrl电子模块驱动拿数据,貌似没用到,而且poll里面也在等待定时器导致定时器卡死 int ret = 0;//::poll(_poll_fds, _poll_fds_num, 0); /* this would be bad... */ if (ret < 0) { DEVICE_LOG("poll error %d\n", ret); } else if (ret == 0) { /* timeout: no control data, switch to failsafe values */ // warnx("no PWM: failsafe\n"); } else { /* get controls for required topics */ unsigned poll_id = 0; for (unsigned i = 0; i < actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS; i++) { if (_control_subs[i] > 0) { if (_poll_fds[poll_id].revents & POLLIN) { orb_copy(_control_topics[i], _control_subs[i], &_controls[i]); } poll_id++; } } /* can we mix? */ if (_mixers != NULL) { size_t num_outputs; switch (_mode) { case MODE_2PWM: num_outputs = 2; break; case MODE_4PWM: num_outputs = 4; break; case MODE_6PWM: num_outputs = 6; break; case MODE_8PWM: num_outputs = 8; break; default: num_outputs = 0; break; } /* do mixing */ float outputs[_max_actuators]; num_outputs = _mixers->mix(outputs, num_outputs, NULL); /* disable unused ports by setting their output to NaN */ for (size_t i = 0; i < sizeof(outputs) / sizeof(outputs[0]); i++) { if (i >= num_outputs) { outputs[i] = NAN_VALUE; } } uint16_t pwm_limited[_max_actuators]; /* the PWM limit call takes care of out of band errors, NaN and constrains */ pwm_limit_calc(_servo_armed, arm_nothrottle(), num_outputs, _reverse_pwm_mask, _disarmed_pwm, _min_pwm, _max_pwm, outputs, pwm_limited, &_pwm_limit); /* output to the servos */ for (size_t i = 0; i < num_outputs; i++) { up_pwm_servo_set(i, pwm_limited[i]); } publish_pwm_outputs(pwm_limited, num_outputs); } } /* check arming state */ bool updated = false; orb_check(_armed_sub, &updated); if (updated) { orb_copy(ORB_ID(actuator_armed), _armed_sub, &_armed); /* update the armed status and check that we're not locked down */ bool set_armed = (_armed.armed || _armed.prearmed) && !_armed.lockdown; if (_servo_armed != set_armed) { _servo_armed = set_armed; } /* update PWM status if armed or if disarmed PWM values are set */ bool pwm_on = (set_armed || _num_disarmed_set > 0); if (_pwm_on != pwm_on) { _pwm_on = pwm_on; up_pwm_servo_arm(pwm_on); } } /* TODO:F orb_check(_param_sub, &updated); if (updated) { parameter_update_s pupdate; orb_copy(ORB_ID(parameter_update), _param_sub, &pupdate); update_pwm_rev_mask(); } */ bool rc_updated = false; #ifdef RC_SERIAL_PORT bool sbus_failsafe, sbus_frame_drop; uint16_t raw_rc_values[input_rc_s::RC_INPUT_MAX_CHANNELS]; uint16_t raw_rc_count; bool sbus_updated = sbus_input(_sbus_fd, &raw_rc_values[0], &raw_rc_count, &sbus_failsafe, &sbus_frame_drop, input_rc_s::RC_INPUT_MAX_CHANNELS); if (sbus_updated) { // we have a new PPM frame. Publish it. _rc_in.channel_count = raw_rc_count; if (_rc_in.channel_count > input_rc_s::RC_INPUT_MAX_CHANNELS) { _rc_in.channel_count = input_rc_s::RC_INPUT_MAX_CHANNELS; } for (uint8_t i = 0; i < _rc_in.channel_count; i++) { _rc_in.values[i] = raw_rc_values[i]; // pilot_info("value[%d]=%d\n", i, _rc_in.values[i]); } _rc_in.timestamp_publication = hrt_absolute_time(); _rc_in.timestamp_last_signal = _rc_in.timestamp_publication; _rc_in.rc_ppm_frame_length = 0; _rc_in.rssi = (!sbus_frame_drop) ? RC_INPUT_RSSI_MAX : 0; _rc_in.rc_failsafe = false; _rc_in.rc_lost = false; _rc_in.rc_lost_frame_count = 0; _rc_in.rc_total_frame_count = 0; rc_updated = true; } #endif #ifdef HRT_PPM_CHANNEL // see if we have new PPM input data if ((ppm_last_valid_decode != _rc_in.timestamp_last_signal) && ppm_decoded_channels > 3) { // we have a new PPM frame. Publish it. _rc_in.channel_count = ppm_decoded_channels; if (_rc_in.channel_count > input_rc_s::RC_INPUT_MAX_CHANNELS) { _rc_in.channel_count = input_rc_s::RC_INPUT_MAX_CHANNELS; } for (uint8_t i = 0; i < _rc_in.channel_count; i++) { _rc_in.values[i] = ppm_buffer[i]; } _rc_in.timestamp_publication = ppm_last_valid_decode; _rc_in.timestamp_last_signal = ppm_last_valid_decode; _rc_in.rc_ppm_frame_length = ppm_frame_length; _rc_in.rssi = RC_INPUT_RSSI_MAX; _rc_in.rc_failsafe = false; _rc_in.rc_lost = false; _rc_in.rc_lost_frame_count = 0; _rc_in.rc_total_frame_count = 0; rc_updated = true; } #endif if (rc_updated) { /* lazily advertise on first publication */ if (_to_input_rc == NULL) { _to_input_rc = orb_advertise(ORB_ID(input_rc), &_rc_in); } else { orb_publish(ORB_ID(input_rc), _to_input_rc, &_rc_in); } } // xTimerStart(_work, (2/portTICK_PERIOD_MS)); }
void UavcanServers::cb_getset(const uavcan::ServiceCallResult<uavcan::protocol::param::GetSet> &result) { if (_count_in_progress) { /* * Currently in parameter count mode: * Iterate over all parameters for the node to which the request was * originally sent, in order to find the maximum parameter ID. If a * request fails, set the node's parameter count to zero. */ uint8_t node_id = result.getCallID().server_node_id.get(); if (result.isSuccessful()) { uavcan::protocol::param::GetSet::Response resp = result.getResponse(); if (resp.name.size()) { _count_index++; _param_counts[node_id] = _count_index; uavcan::protocol::param::GetSet::Request req; req.index = _count_index; int call_res = _param_getset_client.call(result.getCallID().server_node_id, req); if (call_res < 0) { _count_in_progress = false; _count_index = 0; warnx("UAVCAN command bridge: couldn't send GetSet during param count: %d", call_res); } } else { _count_in_progress = false; _count_index = 0; warnx("UAVCAN command bridge: completed param count for node %hhu: %hhu", node_id, _param_counts[node_id]); } } else { _param_counts[node_id] = 0; _count_in_progress = false; _count_index = 0; warnx("UAVCAN command bridge: GetSet error during param count"); } } else { /* * Currently in parameter get/set mode: * Publish a uORB uavcan_parameter_value message containing the current value * of the parameter. */ if (result.isSuccessful()) { uavcan::protocol::param::GetSet::Response param = result.getResponse(); struct uavcan_parameter_value_s response; response.node_id = result.getCallID().server_node_id.get(); strncpy(response.param_id, param.name.c_str(), sizeof(response.param_id) - 1); response.param_id[16] = '\0'; response.param_index = _param_index; response.param_count = _param_counts[response.node_id]; if (param.value.is(uavcan::protocol::param::Value::Tag::integer_value)) { response.param_type = MAV_PARAM_TYPE_INT64; response.int_value = param.value.to<uavcan::protocol::param::Value::Tag::integer_value>(); } else if (param.value.is(uavcan::protocol::param::Value::Tag::real_value)) { response.param_type = MAV_PARAM_TYPE_REAL32; response.real_value = param.value.to<uavcan::protocol::param::Value::Tag::real_value>(); } else if (param.value.is(uavcan::protocol::param::Value::Tag::boolean_value)) { response.param_type = MAV_PARAM_TYPE_UINT8; response.int_value = param.value.to<uavcan::protocol::param::Value::Tag::boolean_value>(); } if (_param_response_pub == nullptr) { _param_response_pub = orb_advertise(ORB_ID(uavcan_parameter_value), &response); } else { orb_publish(ORB_ID(uavcan_parameter_value), _param_response_pub, &response); } } else { warnx("UAVCAN command bridge: GetSet error"); } _param_in_progress = false; _param_index++; } }
/** * This callback is executed each time a waypoint changes. * * It publishes the vehicle_global_position_setpoint_s or the * vehicle_local_position_setpoint_s topic, depending on the type of waypoint */ void mavlink_missionlib_current_waypoint_changed(uint16_t index, float param1, float param2, float param3, float param4, float param5_lat_x, float param6_lon_y, float param7_alt_z, uint8_t frame, uint16_t command) { static orb_advert_t global_position_setpoint_pub = -1; static orb_advert_t global_position_set_triplet_pub = -1; static orb_advert_t local_position_setpoint_pub = -1; static unsigned last_waypoint_index = -1; char buf[50] = {0}; // XXX include check if WP is supported, jump to next if not /* Update controller setpoints */ if (frame == (int)MAV_FRAME_GLOBAL) { /* global, absolute waypoint */ struct vehicle_global_position_setpoint_s sp; sp.lat = param5_lat_x * 1e7f; sp.lon = param6_lon_y * 1e7f; sp.altitude = param7_alt_z; sp.altitude_is_relative = false; sp.yaw = _wrap_pi(param4 / 180.0f * M_PI_F); set_special_fields(param1, param2, param3, param4, command, &sp); /* Initialize setpoint publication if necessary */ if (global_position_setpoint_pub < 0) { global_position_setpoint_pub = orb_advertise(ORB_ID(vehicle_global_position_setpoint), &sp); } else { orb_publish(ORB_ID(vehicle_global_position_setpoint), global_position_setpoint_pub, &sp); } /* fill triplet: previous, current, next waypoint */ struct vehicle_global_position_set_triplet_s triplet; /* current waypoint is same as sp */ memcpy(&(triplet.current), &sp, sizeof(sp)); /* * Check if previous WP (in mission, not in execution order) * is available and identify correct index */ int last_setpoint_index = -1; bool last_setpoint_valid = false; if (index > 0) { last_setpoint_index = index - 1; } while (last_setpoint_index >= 0) { if (wpm->waypoints[last_setpoint_index].frame == (int)MAV_FRAME_GLOBAL && (wpm->waypoints[last_setpoint_index].command == (int)MAV_CMD_NAV_WAYPOINT || wpm->waypoints[last_setpoint_index].command == (int)MAV_CMD_NAV_LOITER_TURNS || wpm->waypoints[last_setpoint_index].command == (int)MAV_CMD_NAV_LOITER_TIME || wpm->waypoints[last_setpoint_index].command == (int)MAV_CMD_NAV_LOITER_UNLIM)) { last_setpoint_valid = true; break; } last_setpoint_index--; } /* * Check if next WP (in mission, not in execution order) * is available and identify correct index */ int next_setpoint_index = -1; bool next_setpoint_valid = false; /* next waypoint */ if (wpm->size > 1) { next_setpoint_index = index + 1; } while (next_setpoint_index < wpm->size - 1) { if (wpm->waypoints[next_setpoint_index].frame == (int)MAV_FRAME_GLOBAL && (wpm->waypoints[next_setpoint_index].command == (int)MAV_CMD_NAV_WAYPOINT || wpm->waypoints[next_setpoint_index].command == (int)MAV_CMD_NAV_LOITER_TURNS || wpm->waypoints[next_setpoint_index].command == (int)MAV_CMD_NAV_LOITER_TIME || wpm->waypoints[next_setpoint_index].command == (int)MAV_CMD_NAV_LOITER_UNLIM)) { next_setpoint_valid = true; break; } next_setpoint_index++; } /* populate last and next */ triplet.previous_valid = false; triplet.next_valid = false; if (last_setpoint_valid) { triplet.previous_valid = true; struct vehicle_global_position_setpoint_s sp; sp.lat = wpm->waypoints[last_setpoint_index].x * 1e7f; sp.lon = wpm->waypoints[last_setpoint_index].y * 1e7f; sp.altitude = wpm->waypoints[last_setpoint_index].z; sp.altitude_is_relative = false; sp.yaw = (wpm->waypoints[last_setpoint_index].param4 / 180.0f) * M_PI_F - M_PI_F; set_special_fields(wpm->waypoints[last_setpoint_index].param1, wpm->waypoints[last_setpoint_index].param2, wpm->waypoints[last_setpoint_index].param3, wpm->waypoints[last_setpoint_index].param4, wpm->waypoints[last_setpoint_index].command, &sp); memcpy(&(triplet.previous), &sp, sizeof(sp)); } if (next_setpoint_valid) { triplet.next_valid = true; struct vehicle_global_position_setpoint_s sp; sp.lat = wpm->waypoints[next_setpoint_index].x * 1e7f; sp.lon = wpm->waypoints[next_setpoint_index].y * 1e7f; sp.altitude = wpm->waypoints[next_setpoint_index].z; sp.altitude_is_relative = false; sp.yaw = (wpm->waypoints[next_setpoint_index].param4 / 180.0f) * M_PI_F - M_PI_F; set_special_fields(wpm->waypoints[next_setpoint_index].param1, wpm->waypoints[next_setpoint_index].param2, wpm->waypoints[next_setpoint_index].param3, wpm->waypoints[next_setpoint_index].param4, wpm->waypoints[next_setpoint_index].command, &sp); memcpy(&(triplet.next), &sp, sizeof(sp)); } /* Initialize triplet publication if necessary */ if (global_position_set_triplet_pub < 0) { global_position_set_triplet_pub = orb_advertise(ORB_ID(vehicle_global_position_set_triplet), &triplet); } else { orb_publish(ORB_ID(vehicle_global_position_set_triplet), global_position_set_triplet_pub, &triplet); } sprintf(buf, "[mp] WP#%i lat: % 3.6f/lon % 3.6f/alt % 4.6f/hdg %3.4f\n", (int)index, (double)param5_lat_x, (double)param6_lon_y, (double)param7_alt_z, (double)param4); } else if (frame == (int)MAV_FRAME_GLOBAL_RELATIVE_ALT) { /* global, relative alt (in relation to HOME) waypoint */ struct vehicle_global_position_setpoint_s sp; sp.lat = param5_lat_x * 1e7f; sp.lon = param6_lon_y * 1e7f; sp.altitude = param7_alt_z; sp.altitude_is_relative = true; sp.yaw = (param4 / 180.0f) * M_PI_F - M_PI_F; set_special_fields(param1, param2, param3, param4, command, &sp); /* Initialize publication if necessary */ if (global_position_setpoint_pub < 0) { global_position_setpoint_pub = orb_advertise(ORB_ID(vehicle_global_position_setpoint), &sp); } else { orb_publish(ORB_ID(vehicle_global_position_setpoint), global_position_setpoint_pub, &sp); } sprintf(buf, "[mp] WP#%i (lat: %f/lon %f/rel alt %f/hdg %f\n", (int)index, (double)param5_lat_x, (double)param6_lon_y, (double)param7_alt_z, (double)param4); } else if (frame == (int)MAV_FRAME_LOCAL_ENU || frame == (int)MAV_FRAME_LOCAL_NED) { /* local, absolute waypoint */ struct vehicle_local_position_setpoint_s sp; sp.x = param5_lat_x; sp.y = param6_lon_y; sp.z = param7_alt_z; sp.yaw = (param4 / 180.0f) * M_PI_F - M_PI_F; /* Initialize publication if necessary */ if (local_position_setpoint_pub < 0) { local_position_setpoint_pub = orb_advertise(ORB_ID(vehicle_local_position_setpoint), &sp); } else { orb_publish(ORB_ID(vehicle_local_position_setpoint), local_position_setpoint_pub, &sp); } sprintf(buf, "[mp] WP#%i (x: %f/y %f/z %f/hdg %f\n", (int)index, (double)param5_lat_x, (double)param6_lon_y, (double)param7_alt_z, (double)param4); } else { warnx("non-navigation WP, ignoring"); mavlink_missionlib_send_gcs_string("[mp] Unknown waypoint type, ignoring."); return; } /* only set this for known waypoint types (non-navigation types would have returned earlier) */ last_waypoint_index = index; mavlink_missionlib_send_gcs_string(buf); printf("%s\n", buf); //printf("[mavlink mp] new setpoint\n");//: frame: %d, lat: %d, lon: %d, alt: %d, yaw: %d\n", frame, param5_lat_x*1000, param6_lon_y*1000, param7_alt_z*1000, param4*1000); }
static int multirotor_pos_control_thread_main(int argc, char *argv[]) { /* welcome user */ warnx("started"); static int mavlink_fd; mavlink_fd = open(MAVLINK_LOG_DEVICE, 0); mavlink_log_info(mavlink_fd, "[mpc] started"); /* structures */ struct vehicle_control_mode_s control_mode; memset(&control_mode, 0, sizeof(control_mode)); struct vehicle_attitude_s att; memset(&att, 0, sizeof(att)); struct vehicle_attitude_setpoint_s att_sp; memset(&att_sp, 0, sizeof(att_sp)); struct manual_control_setpoint_s manual; memset(&manual, 0, sizeof(manual)); struct vehicle_local_position_s local_pos; memset(&local_pos, 0, sizeof(local_pos)); struct vehicle_local_position_setpoint_s local_pos_sp; memset(&local_pos_sp, 0, sizeof(local_pos_sp)); struct vehicle_global_position_setpoint_s global_pos_sp; memset(&global_pos_sp, 0, sizeof(local_pos_sp)); struct vehicle_global_velocity_setpoint_s global_vel_sp; memset(&global_vel_sp, 0, sizeof(global_vel_sp)); /* subscribe to attitude, motor setpoints and system state */ int param_sub = orb_subscribe(ORB_ID(parameter_update)); int control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode)); int att_sub = orb_subscribe(ORB_ID(vehicle_attitude)); int att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint)); int manual_sub = orb_subscribe(ORB_ID(manual_control_setpoint)); int local_pos_sp_sub = orb_subscribe(ORB_ID(vehicle_local_position_setpoint)); int local_pos_sub = orb_subscribe(ORB_ID(vehicle_local_position)); int global_pos_sp_sub = orb_subscribe(ORB_ID(vehicle_global_position_setpoint)); /* publish setpoint */ orb_advert_t local_pos_sp_pub = orb_advertise(ORB_ID(vehicle_local_position_setpoint), &local_pos_sp); 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 reset_mission_sp = false; bool global_pos_sp_valid = false; 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_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; const float pos_ctl_dz = 0.05f; float ref_alt = 0.0f; hrt_abstime ref_alt_t = 0; uint64_t local_ref_timestamp = 0; PID_t xy_pos_pids[2]; PID_t xy_vel_pids[2]; PID_t z_pos_pid; thrust_pid_t z_vel_pid; thread_running = true; struct multirotor_position_control_params params; struct multirotor_position_control_param_handles params_h; parameters_init(¶ms_h); parameters_update(¶ms_h, ¶ms); for (int i = 0; i < 2; i++) { pid_init(&(xy_pos_pids[i]), params.xy_p, 0.0f, params.xy_d, 1.0f, 0.0f, PID_MODE_DERIVATIV_SET, 0.02f); pid_init(&(xy_vel_pids[i]), params.xy_vel_p, params.xy_vel_i, params.xy_vel_d, 1.0f, params.tilt_max, PID_MODE_DERIVATIV_CALC_NO_SP, 0.02f); } pid_init(&z_pos_pid, params.z_p, 0.0f, params.z_d, 1.0f, params.z_vel_max, PID_MODE_DERIVATIV_SET, 0.02f); thrust_pid_init(&z_vel_pid, params.z_vel_p, params.z_vel_i, params.z_vel_d, -params.thr_max, -params.thr_min, PID_MODE_DERIVATIV_CALC_NO_SP, 0.02f); while (!thread_should_exit) { bool param_updated; orb_check(param_sub, ¶m_updated); if (param_updated) { /* clear updated flag */ struct parameter_update_s ps; orb_copy(ORB_ID(parameter_update), param_sub, &ps); /* update params */ parameters_update(¶ms_h, ¶ms); for (int i = 0; i < 2; i++) { pid_set_parameters(&(xy_pos_pids[i]), params.xy_p, 0.0f, params.xy_d, 1.0f, 0.0f); /* use integral_limit_out = tilt_max / 2 */ float i_limit; if (params.xy_vel_i > 0.0f) { i_limit = params.tilt_max / params.xy_vel_i / 2.0f; } else { 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); } pid_set_parameters(&z_pos_pid, params.z_p, 0.0f, params.z_d, 1.0f, params.z_vel_max); thrust_pid_set_parameters(&z_vel_pid, params.z_vel_p, params.z_vel_i, params.z_vel_d, -params.thr_max, -params.thr_min); } bool updated; orb_check(control_mode_sub, &updated); if (updated) { orb_copy(ORB_ID(vehicle_control_mode), control_mode_sub, &control_mode); } orb_check(global_pos_sp_sub, &updated); if (updated) { orb_copy(ORB_ID(vehicle_global_position_setpoint), global_pos_sp_sub, &global_pos_sp); global_pos_sp_valid = true; reset_mission_sp = true; } hrt_abstime t = hrt_absolute_time(); float dt; if (t_prev != 0) { dt = (t - t_prev) * 0.000001f; } else { dt = 0.0f; } if (control_mode.flag_armed && !was_armed) { /* reset setpoints and integrals on arming */ 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; } was_armed = control_mode.flag_armed; t_prev = t; if (control_mode.flag_control_altitude_enabled || control_mode.flag_control_velocity_enabled || control_mode.flag_control_position_enabled) { orb_copy(ORB_ID(manual_control_setpoint), manual_sub, &manual); orb_copy(ORB_ID(vehicle_attitude), att_sub, &att); orb_copy(ORB_ID(vehicle_attitude_setpoint), att_sp_sub, &att_sp); orb_copy(ORB_ID(vehicle_local_position), local_pos_sub, &local_pos); float z_sp_offs_max = params.z_vel_max / params.z_p * 2.0f; float xy_sp_offs_max = params.xy_vel_max / params.xy_p * 2.0f; float sp_move_rate[3] = { 0.0f, 0.0f, 0.0f }; if (control_mode.flag_control_manual_enabled) { /* manual control */ /* check for reference point updates and correct setpoint */ if (local_pos.ref_timestamp != ref_alt_t) { if (ref_alt_t != 0) { /* home alt changed, don't follow large ground level changes in manual flight */ local_pos_sp.z += local_pos.ref_alt - ref_alt; } ref_alt_t = local_pos.ref_timestamp; ref_alt = local_pos.ref_alt; // TODO also correct XY setpoint } /* reset setpoints to current position if needed */ if (control_mode.flag_control_altitude_enabled) { 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); } /* move altitude setpoint with throttle stick */ float z_sp_ctl = scale_control(manual.throttle - 0.5f, 0.5f, alt_ctl_dz); if (z_sp_ctl != 0.0f) { sp_move_rate[2] = -z_sp_ctl * params.z_vel_max; local_pos_sp.z += sp_move_rate[2] * dt; if (local_pos_sp.z > local_pos.z + z_sp_offs_max) { local_pos_sp.z = local_pos.z + z_sp_offs_max; } else if (local_pos_sp.z < local_pos.z - z_sp_offs_max) { local_pos_sp.z = local_pos.z - z_sp_offs_max; } } } if (control_mode.flag_control_position_enabled) { 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]); pid_reset_integral(&xy_vel_pids[1]); mavlink_log_info(mavlink_fd, "[mpc] reset pos sp: %.2f, %.2f", (double)local_pos_sp.x, (double)local_pos_sp.y); } /* move position setpoint with roll/pitch stick */ float pos_pitch_sp_ctl = scale_control(-manual.pitch / params.rc_scale_pitch, 1.0f, pos_ctl_dz); float pos_roll_sp_ctl = scale_control(manual.roll / params.rc_scale_roll, 1.0f, pos_ctl_dz); if (pos_pitch_sp_ctl != 0.0f || pos_roll_sp_ctl != 0.0f) { /* calculate direction and increment of control in NED frame */ float xy_sp_ctl_dir = att.yaw + atan2f(pos_roll_sp_ctl, pos_pitch_sp_ctl); float xy_sp_ctl_speed = norm(pos_pitch_sp_ctl, pos_roll_sp_ctl) * params.xy_vel_max; sp_move_rate[0] = cosf(xy_sp_ctl_dir) * xy_sp_ctl_speed; sp_move_rate[1] = sinf(xy_sp_ctl_dir) * xy_sp_ctl_speed; local_pos_sp.x += sp_move_rate[0] * dt; local_pos_sp.y += sp_move_rate[1] * dt; /* limit maximum setpoint from position offset and preserve direction * fail safe, should not happen in normal operation */ float pos_vec_x = local_pos_sp.x - local_pos.x; float pos_vec_y = local_pos_sp.y - local_pos.y; float pos_vec_norm = norm(pos_vec_x, pos_vec_y) / xy_sp_offs_max; if (pos_vec_norm > 1.0f) { local_pos_sp.x = local_pos.x + pos_vec_x / pos_vec_norm; local_pos_sp.y = local_pos.y + pos_vec_y / pos_vec_norm; } } } local_pos_sp.yaw = att_sp.yaw_body; /* 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 */ 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_sp_xy = true; reset_auto_sp_z = true; } else if (control_mode.auto_state == NAVIGATION_STATE_AUTO_TAKEOFF) { 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; att_sp.yaw_body = att.yaw; 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_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) { 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; map_projection_init(lat_home, lon_home); mavlink_log_info(mavlink_fd, "[mpc] local pos ref: %.7f, %.7f", (double)lat_home, (double)lon_home); } if (reset_mission_sp) { reset_mission_sp = false; /* update global setpoint projection */ if (global_pos_sp_valid) { /* global position setpoint valid, use it */ double sp_lat = global_pos_sp.lat * 1e-7; double sp_lon = global_pos_sp.lon * 1e-7; /* project global setpoint to local setpoint */ map_projection_project(sp_lat, sp_lon, &(local_pos_sp.x), &(local_pos_sp.y)); if (global_pos_sp.altitude_is_relative) { local_pos_sp.z = -global_pos_sp.altitude; } else { local_pos_sp.z = local_pos.ref_alt - global_pos_sp.altitude; } local_pos_sp.yaw = global_pos_sp.yaw; att_sp.yaw_body = global_pos_sp.yaw; 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 (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.yaw = att.yaw; 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_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) { reset_mission_sp = true; } /* reset setpoints after AUTO mode */ reset_man_sp_xy = true; reset_man_sp_z = true; } else { /* no control (failsafe), loiter or stay on ground */ if (local_pos.landed) { /* landed: move setpoint down */ /* in air: hold altitude */ if (local_pos_sp.z < 5.0f) { /* set altitude setpoint to 5m under ground, * don't set it too deep to avoid unexpected landing in case of false "landed" signal */ local_pos_sp.z = 5.0f; mavlink_log_info(mavlink_fd, "[mpc] landed, set alt: %.2f", (double) - local_pos_sp.z); } reset_man_sp_z = true; } else { /* in air: hold altitude */ 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_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; 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; } } /* publish local position setpoint */ orb_publish(ORB_ID(vehicle_local_position_setpoint), local_pos_sp_pub, &local_pos_sp); /* run position & altitude controllers, calculate velocity setpoint */ if (control_mode.flag_control_altitude_enabled) { 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_man_sp_z = true; global_vel_sp.vz = 0.0f; } if (control_mode.flag_control_position_enabled) { /* calculate velocity set point in NED frame */ global_vel_sp.vx = pid_calculate(&xy_pos_pids[0], local_pos_sp.x, local_pos.x, local_pos.vx - sp_move_rate[0], dt) + sp_move_rate[0]; global_vel_sp.vy = pid_calculate(&xy_pos_pids[1], local_pos_sp.y, local_pos.y, local_pos.vy - sp_move_rate[1], dt) + sp_move_rate[1]; /* limit horizontal speed */ float xy_vel_sp_norm = norm(global_vel_sp.vx, global_vel_sp.vy) / params.xy_vel_max; if (xy_vel_sp_norm > 1.0f) { global_vel_sp.vx /= xy_vel_sp_norm; global_vel_sp.vy /= xy_vel_sp_norm; } } else { reset_man_sp_xy = true; global_vel_sp.vx = 0.0f; global_vel_sp.vy = 0.0f; } /* publish new velocity setpoint */ orb_publish(ORB_ID(vehicle_global_velocity_setpoint), global_vel_sp_pub, &global_vel_sp); // TODO subscribe to velocity setpoint if altitude/position control disabled if (control_mode.flag_control_climb_rate_enabled || control_mode.flag_control_velocity_enabled) { /* run velocity controllers, calculate thrust vector with attitude-thrust compensation */ float thrust_sp[3] = { 0.0f, 0.0f, 0.0f }; if (control_mode.flag_control_climb_rate_enabled) { if (reset_int_z) { reset_int_z = false; float i = params.thr_min; if (reset_int_z_manual) { i = manual.throttle; if (i < params.thr_min) { i = params.thr_min; } else if (i > params.thr_max) { i = params.thr_max; } } thrust_pid_set_integral(&z_vel_pid, -i); mavlink_log_info(mavlink_fd, "[mpc] reset hovering thrust: %.2f", (double)i); } thrust_sp[2] = thrust_pid_calculate(&z_vel_pid, global_vel_sp.vz, local_pos.vz, dt, att.R[2][2]); att_sp.thrust = -thrust_sp[2]; } else { /* reset thrust integral when altitude control enabled */ reset_int_z = true; } if (control_mode.flag_control_velocity_enabled) { /* calculate thrust set point in NED frame */ if (reset_int_xy) { reset_int_xy = false; pid_reset_integral(&xy_vel_pids[0]); pid_reset_integral(&xy_vel_pids[1]); mavlink_log_info(mavlink_fd, "[mpc] reset pos integral"); } thrust_sp[0] = pid_calculate(&xy_vel_pids[0], global_vel_sp.vx, local_pos.vx, 0.0f, dt); thrust_sp[1] = pid_calculate(&xy_vel_pids[1], global_vel_sp.vy, local_pos.vy, 0.0f, dt); /* thrust_vector now contains desired acceleration (but not in m/s^2) in NED frame */ /* limit horizontal part of thrust */ float thrust_xy_dir = atan2f(thrust_sp[1], thrust_sp[0]); /* assuming that vertical component of thrust is g, * horizontal component = g * tan(alpha) */ float tilt = atanf(norm(thrust_sp[0], thrust_sp[1])); if (tilt > params.tilt_max) { tilt = params.tilt_max; } /* convert direction to body frame */ thrust_xy_dir -= att.yaw; /* calculate roll and pitch */ att_sp.roll_body = sinf(thrust_xy_dir) * tilt; att_sp.pitch_body = -cosf(thrust_xy_dir) * tilt / cosf(att_sp.roll_body); } else { reset_int_xy = true; } att_sp.timestamp = hrt_absolute_time(); /* publish new attitude setpoint */ orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp); } } else { /* position controller disabled, reset setpoints */ reset_man_sp_z = true; reset_man_sp_xy = true; reset_int_z = true; reset_int_xy = 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 */ reset_int_z_manual = control_mode.flag_armed && control_mode.flag_control_manual_enabled && !control_mode.flag_control_climb_rate_enabled; /* run at approximately 50 Hz */ usleep(20000); } warnx("stopped"); mavlink_log_info(mavlink_fd, "[mpc] stopped"); thread_running = false; fflush(stdout); return 0; }