Browse Source

Merge branch 'multirotor' of github.com:cvg/Firmware_Private into multirotor

sbg
Lorenz Meier 12 years ago
parent
commit
31dcd5a16d
  1. 9
      ROMFS/px4fmu_common/init.d/30_io_camflyer
  2. 7
      ROMFS/px4fmu_common/init.d/31_io_phantom
  3. 5
      ROMFS/px4fmu_common/init.d/rc.multirotor
  4. 11
      ROMFS/px4fmu_common/init.d/rcS
  5. 2
      src/modules/att_pos_estimator_ekf/KalmanNav.cpp
  6. 14
      src/modules/commander/commander.cpp
  7. 1
      src/modules/commander/state_machine_helper.cpp
  8. 2
      src/modules/mavlink/orb_listener.c
  9. 40
      src/modules/mavlink/waypoints.c
  10. 101
      src/modules/multirotor_pos_control/multirotor_pos_control.c
  11. 3
      src/modules/position_estimator_inav/position_estimator_inav_main.c
  12. 2
      src/modules/uORB/topics/vehicle_control_mode.h
  13. 3
      src/modules/uORB/topics/vehicle_global_position.h
  14. 2
      src/modules/uORB/topics/vehicle_local_position.h

9
ROMFS/px4fmu_common/init.d/30_io_camflyer

@ -1,6 +1,6 @@
#!nsh #!nsh
cho "[init] 30_io_camflyer: PX4FMU+PX4IO on Camflyer" echo "[init] 30_io_camflyer: PX4FMU+PX4IO on Camflyer"
# #
# Load default params for this platform # Load default params for this platform
@ -49,6 +49,11 @@ px4io limit 100
# Start the sensors (depends on orb, px4io) # Start the sensors (depends on orb, px4io)
# #
sh /etc/init.d/rc.sensors sh /etc/init.d/rc.sensors
#
# Start logging (depends on sensors)
#
sh /etc/init.d/rc.logging
# #
# Start GPS interface (depends on orb) # Start GPS interface (depends on orb)
@ -64,4 +69,4 @@ kalman_demo start
# Load mixer and start controllers (depends on px4io) # Load mixer and start controllers (depends on px4io)
# #
mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
control_demo start fw_att_control start

7
ROMFS/px4fmu_common/init.d/31_io_phantom

@ -44,6 +44,11 @@ commander start
# Start the sensors # Start the sensors
# #
sh /etc/init.d/rc.sensors sh /etc/init.d/rc.sensors
#
# Start logging (depends on sensors)
#
sh /etc/init.d/rc.logging
# #
# Start GPS interface # Start GPS interface
@ -59,4 +64,4 @@ kalman_demo start
# Load mixer and start controllers (depends on px4io) # Load mixer and start controllers (depends on px4io)
# #
mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
control_demo start fw_att_control start

5
ROMFS/px4fmu_common/init.d/rc.multirotor

@ -8,6 +8,11 @@
# #
sh /etc/init.d/rc.sensors sh /etc/init.d/rc.sensors
#
# Start logging (depends on sensors)
#
sh /etc/init.d/rc.logging
# #
# Start the commander. # Start the commander.
# #

11
ROMFS/px4fmu_common/init.d/rcS

@ -103,11 +103,9 @@ then
blinkm systemstate blinkm systemstate
fi fi
fi fi
# # Try to get an USB console
# Start logging nshterm /dev/ttyACM0 &
#
sh /etc/init.d/rc.logging
# #
# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell) # Check if PX4IO Firmware should be upgraded (from Andrew Tridgell)
@ -183,9 +181,6 @@ then
set MODE custom set MODE custom
fi fi
# Try to get an USB console
nshterm /dev/ttyACM0 &
# Start any custom extensions that might be missing # Start any custom extensions that might be missing
if [ -f /fs/microsd/etc/rc.local ] if [ -f /fs/microsd/etc/rc.local ]
then then

2
src/modules/att_pos_estimator_ekf/KalmanNav.cpp

@ -325,7 +325,7 @@ void KalmanNav::updatePublications()
_pos.vx = vN; _pos.vx = vN;
_pos.vy = vE; _pos.vy = vE;
_pos.vz = vD; _pos.vz = vD;
_pos.hdg = psi; _pos.yaw = psi;
// attitude publication // attitude publication
_att.timestamp = _pubTimeStamp; _att.timestamp = _pubTimeStamp;

14
src/modules/commander/commander.cpp

@ -210,7 +210,7 @@ void print_reject_arm(const char *msg);
void print_status(); void print_status();
transition_result_t check_navigation_state_machine(struct vehicle_status_s *current_status, struct vehicle_control_mode_s *control_mode); transition_result_t check_navigation_state_machine(struct vehicle_status_s *current_status, struct vehicle_control_mode_s *control_mode, struct vehicle_local_position_s *local_pos);
/** /**
* Loop that runs at a lower rate and priority for calibration and parameter tasks. * Loop that runs at a lower rate and priority for calibration and parameter tasks.
@ -1214,7 +1214,7 @@ int commander_thread_main(int argc, char *argv[])
} }
/* evaluate the navigation state machine */ /* evaluate the navigation state machine */
transition_result_t res = check_navigation_state_machine(&status, &control_mode); transition_result_t res = check_navigation_state_machine(&status, &control_mode, &local_position);
if (res == TRANSITION_DENIED) { if (res == TRANSITION_DENIED) {
/* DENIED here indicates bug in the commander */ /* DENIED here indicates bug in the commander */
@ -1572,7 +1572,7 @@ print_reject_arm(const char *msg)
} }
transition_result_t transition_result_t
check_navigation_state_machine(struct vehicle_status_s *current_status, struct vehicle_control_mode_s *control_mode) check_navigation_state_machine(struct vehicle_status_s *current_status, struct vehicle_control_mode_s *control_mode, struct vehicle_local_position_s *local_pos)
{ {
transition_result_t res = TRANSITION_DENIED; transition_result_t res = TRANSITION_DENIED;
@ -1592,8 +1592,12 @@ check_navigation_state_machine(struct vehicle_status_s *current_status, struct v
case MAIN_STATE_AUTO: case MAIN_STATE_AUTO:
if (current_status->arming_state == ARMING_STATE_ARMED || current_status->arming_state == ARMING_STATE_ARMED_ERROR) { if (current_status->arming_state == ARMING_STATE_ARMED || current_status->arming_state == ARMING_STATE_ARMED_ERROR) {
if (current_status->navigation_state == NAVIGATION_STATE_AUTO_TAKEOFF) { if (current_status->navigation_state == NAVIGATION_STATE_AUTO_TAKEOFF) {
/* don't act while taking off */ /* check if takeoff completed */
res = TRANSITION_NOT_CHANGED; if (local_pos->z < -5.0f && !status.condition_landed) {
res = navigation_state_transition(current_status, NAVIGATION_STATE_AUTO_LOITER, control_mode);
} else {
res = TRANSITION_NOT_CHANGED;
}
} else { } else {
if (current_status->condition_landed) { if (current_status->condition_landed) {

1
src/modules/commander/state_machine_helper.cpp

@ -413,6 +413,7 @@ navigation_state_transition(struct vehicle_status_s *current_status, navigation_
if (ret == TRANSITION_CHANGED) { if (ret == TRANSITION_CHANGED) {
current_status->navigation_state = new_navigation_state; current_status->navigation_state = new_navigation_state;
control_mode->auto_state = current_status->navigation_state;
navigation_state_changed = true; navigation_state_changed = true;
} }
} }

2
src/modules/mavlink/orb_listener.c

@ -341,7 +341,7 @@ l_global_position(const struct listener *l)
int16_t vz = (int16_t)(global_pos.vz * 100.0f); int16_t vz = (int16_t)(global_pos.vz * 100.0f);
/* heading in degrees * 10, from 0 to 36.000) */ /* heading in degrees * 10, from 0 to 36.000) */
uint16_t hdg = (global_pos.hdg / M_PI_F) * (180.0f * 10.0f) + (180.0f * 10.0f); uint16_t hdg = (global_pos.yaw / M_PI_F) * (180.0f * 10.0f) + (180.0f * 10.0f);
mavlink_msg_global_position_int_send(MAVLINK_COMM_0, mavlink_msg_global_position_int_send(MAVLINK_COMM_0,
timestamp / 1000, timestamp / 1000,

40
src/modules/mavlink/waypoints.c

@ -294,16 +294,13 @@ void mavlink_wpm_send_waypoint_reached(uint16_t seq)
*/ */
float mavlink_wpm_distance_to_point_global_wgs84(uint16_t seq, float lat, float lon, float alt) float mavlink_wpm_distance_to_point_global_wgs84(uint16_t seq, float lat, float lon, float alt)
{ {
//TODO: implement for z once altidude contoller is implemented
static uint16_t counter; static uint16_t counter;
// if(counter % 10 == 0) printf(" x = %.10f, y = %.10f\n", x, y);
if (seq < wpm->size) { if (seq < wpm->size) {
mavlink_mission_item_t *cur = &(wpm->waypoints[seq]); mavlink_mission_item_t *wp = &(wpm->waypoints[seq]);
double current_x_rad = cur->x / 180.0 * M_PI; double current_x_rad = wp->x / 180.0 * M_PI;
double current_y_rad = cur->y / 180.0 * M_PI; double current_y_rad = wp->y / 180.0 * M_PI;
double x_rad = lat / 180.0 * M_PI; double x_rad = lat / 180.0 * M_PI;
double y_rad = lon / 180.0 * M_PI; double y_rad = lon / 180.0 * M_PI;
@ -315,7 +312,10 @@ float mavlink_wpm_distance_to_point_global_wgs84(uint16_t seq, float lat, float
const double radius_earth = 6371000.0; const double radius_earth = 6371000.0;
return radius_earth * c; float dxy = radius_earth * c;
float dz = alt - wp->z;
return sqrtf(dxy * dxy + dz * dz);
} else { } else {
return -1.0f; return -1.0f;
@ -383,21 +383,19 @@ void check_waypoints_reached(uint64_t now, const struct vehicle_global_position_
// XXX TODO // XXX TODO
} }
if (dist >= 0.f && dist <= orbit /*&& wpm->yaw_reached*/) { //TODO implement yaw if (dist >= 0.f && dist <= orbit) {
wpm->pos_reached = true; wpm->pos_reached = true;
} }
// check if required yaw reached
// else float yaw_sp = _wrap_pi(wpm->waypoints[wpm->current_active_wp_id].param4 / 180.0f * FM_PI);
// { float yaw_err = _wrap_pi(yaw_sp - local_pos->yaw);
// if(counter % 100 == 0) if (fabsf(yaw_err) < 0.05f) {
// printf("Setpoint not reached yet: %0.4f, orbit: %.4f, coordinate frame: %d\n",dist, orbit, coordinate_frame); wpm->yaw_reached = true;
// } }
} }
//check if the current waypoint was reached //check if the current waypoint was reached
if (wpm->pos_reached /*wpm->yaw_reached &&*/ && !wpm->idle) { if (wpm->pos_reached && /*wpm->yaw_reached &&*/ !wpm->idle) {
if (wpm->current_active_wp_id < wpm->size) { if (wpm->current_active_wp_id < wpm->size) {
mavlink_mission_item_t *cur_wp = &(wpm->waypoints[wpm->current_active_wp_id]); mavlink_mission_item_t *cur_wp = &(wpm->waypoints[wpm->current_active_wp_id]);
@ -412,11 +410,7 @@ void check_waypoints_reached(uint64_t now, const struct vehicle_global_position_
bool time_elapsed = false; bool time_elapsed = false;
if (cur_wp->command == (int)MAV_CMD_NAV_LOITER_TIME) { if (now - wpm->timestamp_firstinside_orbit >= cur_wp->param1 * 1000 * 1000) {
if (now - wpm->timestamp_firstinside_orbit >= cur_wp->param1 * 1000 * 1000) {
time_elapsed = true;
}
} else if (now - wpm->timestamp_firstinside_orbit >= cur_wp->param1 * 1000 * 1000) {
time_elapsed = true; time_elapsed = true;
} else if (cur_wp->command == (int)MAV_CMD_NAV_TAKEOFF) { } else if (cur_wp->command == (int)MAV_CMD_NAV_TAKEOFF) {
time_elapsed = true; time_elapsed = true;
@ -493,7 +487,7 @@ int mavlink_waypoint_eventloop(uint64_t now, const struct vehicle_global_positio
// mavlink_wpm_send_setpoint(wpm->current_active_wp_id); // mavlink_wpm_send_setpoint(wpm->current_active_wp_id);
// } // }
check_waypoints_reached(now, global_position , local_position); check_waypoints_reached(now, global_position, local_position);
return OK; return OK;
} }

101
src/modules/multirotor_pos_control/multirotor_pos_control.c

@ -54,6 +54,7 @@
#include <drivers/drv_hrt.h> #include <drivers/drv_hrt.h>
#include <uORB/uORB.h> #include <uORB/uORB.h>
#include <uORB/topics/parameter_update.h> #include <uORB/topics/parameter_update.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/vehicle_control_mode.h> #include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/vehicle_attitude.h> #include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/manual_control_setpoint.h> #include <uORB/topics/manual_control_setpoint.h>
@ -221,11 +222,12 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
bool reset_int_xy = true; bool reset_int_xy = true;
bool was_armed = false; bool was_armed = false;
bool reset_integral = true; bool reset_integral = true;
bool reset_auto_pos = true;
hrt_abstime t_prev = 0; hrt_abstime t_prev = 0;
/* integrate in NED frame to estimate wind but not attitude offset */
const float alt_ctl_dz = 0.2f; const float alt_ctl_dz = 0.2f;
const float pos_ctl_dz = 0.05f; const float pos_ctl_dz = 0.05f;
const float takeoff_alt_default = 10.0f;
float ref_alt = 0.0f; float ref_alt = 0.0f;
hrt_abstime ref_alt_t = 0; hrt_abstime ref_alt_t = 0;
uint64_t local_ref_timestamp = 0; uint64_t local_ref_timestamp = 0;
@ -414,50 +416,76 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
} else { } else {
/* non-manual mode, use global setpoint */ /* non-manual mode, use global setpoint */
/* init local projection using local position ref */ if (control_mode.auto_state == NAVIGATION_STATE_AUTO_TAKEOFF) {
if (local_pos.ref_timestamp != local_ref_timestamp) { if (reset_auto_pos) {
global_pos_sp_reproject = true; local_pos_sp.x = local_pos.x;
local_ref_timestamp = local_pos.ref_timestamp; local_pos_sp.y = local_pos.y;
double lat_home = local_pos.ref_lat * 1e-7; local_pos_sp.z = -takeoff_alt_default;
double lon_home = local_pos.ref_lon * 1e-7; att_sp.yaw_body = att.yaw;
map_projection_init(lat_home, lon_home); reset_auto_pos = false;
mavlink_log_info(mavlink_fd, "[mpc] local pos ref: %.7f, %.7f", lat_home, lon_home); }
} } else if (control_mode.auto_state == NAVIGATION_STATE_AUTO_LOITER) {
if (reset_auto_pos) {
if (global_pos_sp_reproject) { local_pos_sp.x = local_pos.x;
/* update global setpoint projection */ local_pos_sp.y = local_pos.y;
global_pos_sp_reproject = false; local_pos_sp.z = local_pos.z;
att_sp.yaw_body = att.yaw;
reset_auto_pos = false;
}
} else if (control_mode.auto_state == NAVIGATION_STATE_AUTO_RTL) {
// TODO
reset_auto_pos = true;
} else if (control_mode.auto_state == NAVIGATION_STATE_AUTO_MISSION) {
/* init local projection using local position ref */
if (local_pos.ref_timestamp != local_ref_timestamp) {
global_pos_sp_reproject = true;
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", lat_home, lon_home);
}
if (global_pos_sp_valid) { if (global_pos_sp_reproject) {
/* global position setpoint valid, use it */ /* update global setpoint projection */
double sp_lat = global_pos_sp.lat * 1e-7; global_pos_sp_reproject = false;
double sp_lon = global_pos_sp.lon * 1e-7; if (global_pos_sp_valid) {
/* project global setpoint to local setpoint */ /* global position setpoint valid, use it */
map_projection_project(sp_lat, sp_lon, &(local_pos_sp.x), &(local_pos_sp.y)); 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;
}
if (global_pos_sp.altitude_is_relative) { mavlink_log_info(mavlink_fd, "[mpc] new sp: %.7f, %.7f (%.2f, %.2f)", sp_lat, sp_lon, local_pos_sp.x, local_pos_sp.y);
local_pos_sp.z = -global_pos_sp.altitude;
} else { } else {
local_pos_sp.z = local_pos.ref_alt - global_pos_sp.altitude; if (!local_pos_sp_valid) {
} /* local position setpoint is invalid,
* use current position as setpoint for loiter */
mavlink_log_info(mavlink_fd, "[mpc] new sp: %.7f, %.7f (%.2f, %.2f)", sp_lat, sp_lon, local_pos_sp.x, local_pos_sp.y); local_pos_sp.x = local_pos.x;
local_pos_sp.y = local_pos.y;
local_pos_sp.z = local_pos.z;
}
} else { mavlink_log_info(mavlink_fd, "[mpc] no global pos sp, loiter: %.2f, %.2f", local_pos_sp.x, local_pos_sp.y);
if (!local_pos_sp_valid) {
/* local position setpoint is invalid,
* use current position as setpoint for loiter */
local_pos_sp.x = local_pos.x;
local_pos_sp.y = local_pos.y;
local_pos_sp.z = local_pos.z;
} }
mavlink_log_info(mavlink_fd, "[mpc] no global pos sp, loiter: %.2f, %.2f", local_pos_sp.x, local_pos_sp.y); /* publish local position setpoint as projection of global position setpoint */
orb_publish(ORB_ID(vehicle_local_position_setpoint), local_pos_sp_pub, &local_pos_sp);
} }
att_sp.yaw_body = global_pos_sp.yaw;
reset_auto_pos = true;
}
/* publish local position setpoint as projection of global position setpoint */ if (control_mode.auto_state != NAVIGATION_STATE_AUTO_MISSION) {
orb_publish(ORB_ID(vehicle_local_position_setpoint), local_pos_sp_pub, &local_pos_sp); global_pos_sp_reproject = true;
} }
/* reset setpoints after non-manual modes */ /* reset setpoints after non-manual modes */
@ -575,6 +603,7 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
reset_int_z = true; reset_int_z = true;
reset_int_xy = true; reset_int_xy = true;
global_pos_sp_reproject = true; global_pos_sp_reproject = true;
reset_auto_pos = true;
} }
/* reset altitude controller integral (hovering throttle) to manual throttle after manual throttle control */ /* reset altitude controller integral (hovering throttle) to manual throttle after manual throttle control */

3
src/modules/position_estimator_inav/position_estimator_inav_main.c

@ -591,6 +591,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
local_pos.z = z_est[0]; local_pos.z = z_est[0];
local_pos.vz = z_est[1]; local_pos.vz = z_est[1];
local_pos.landed = landed; local_pos.landed = landed;
local_pos.yaw = att.yaw;
orb_publish(ORB_ID(vehicle_local_position), vehicle_local_position_pub, &local_pos); orb_publish(ORB_ID(vehicle_local_position), vehicle_local_position_pub, &local_pos);
@ -609,7 +610,6 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
if (local_pos.v_xy_valid) { if (local_pos.v_xy_valid) {
global_pos.vx = local_pos.vx; global_pos.vx = local_pos.vx;
global_pos.vy = local_pos.vy; global_pos.vy = local_pos.vy;
global_pos.hdg = atan2f(local_pos.vy, local_pos.vx); // TODO is it correct?
} }
if (local_pos.z_valid) { if (local_pos.z_valid) {
@ -623,6 +623,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
if (local_pos.v_z_valid) { if (local_pos.v_z_valid) {
global_pos.vz = local_pos.vz; global_pos.vz = local_pos.vz;
} }
global_pos.yaw = local_pos.yaw;
global_pos.timestamp = t; global_pos.timestamp = t;

2
src/modules/uORB/topics/vehicle_control_mode.h

@ -82,6 +82,8 @@ struct vehicle_control_mode_s
bool failsave_lowlevel; /**< Set to true if low-level failsafe mode is enabled */ bool failsave_lowlevel; /**< Set to true if low-level failsafe mode is enabled */
bool failsave_highlevel; /**< Set to true if high-level failsafe mode is enabled */ bool failsave_highlevel; /**< Set to true if high-level failsafe mode is enabled */
uint8_t auto_state; // TEMP navigation state for AUTO modes
}; };
/** /**

3
src/modules/uORB/topics/vehicle_global_position.h

@ -72,8 +72,7 @@ struct vehicle_global_position_s
float vx; /**< Ground X velocity, m/s in NED */ float vx; /**< Ground X velocity, m/s in NED */
float vy; /**< Ground Y velocity, m/s in NED */ float vy; /**< Ground Y velocity, m/s in NED */
float vz; /**< Ground Z velocity, m/s in NED */ float vz; /**< Ground Z velocity, m/s in NED */
float hdg; /**< Compass heading in radians -PI..+PI. */ float yaw; /**< Compass heading in radians -PI..+PI. */
}; };
/** /**

2
src/modules/uORB/topics/vehicle_local_position.h

@ -67,6 +67,8 @@ struct vehicle_local_position_s
float vx; /**< Ground X Speed (Latitude), m/s in NED */ float vx; /**< Ground X Speed (Latitude), m/s in NED */
float vy; /**< Ground Y Speed (Longitude), m/s in NED */ float vy; /**< Ground Y Speed (Longitude), m/s in NED */
float vz; /**< Ground Z Speed (Altitude), m/s in NED */ float vz; /**< Ground Z Speed (Altitude), m/s in NED */
/* Heading */
float yaw;
/* Reference position in GPS / WGS84 frame */ /* Reference position in GPS / WGS84 frame */
bool global_xy; /**< true if position (x, y) is valid and has valid global reference (ref_lat, ref_lon) */ bool global_xy; /**< true if position (x, y) is valid and has valid global reference (ref_lat, ref_lon) */
bool global_z; /**< true if z is valid and has valid global reference (ref_alt) */ bool global_z; /**< true if z is valid and has valid global reference (ref_alt) */

Loading…
Cancel
Save