Merge branch 'master' of https://github.com/PX4/Firmware into fw_control

This commit is contained in:
Thomas Gubler 2012-11-10 18:35:58 +01:00
commit e1cfa102a2
4 changed files with 31 additions and 94 deletions

View File

@ -58,6 +58,7 @@
#include <uORB/topics/debug_key_value.h> #include <uORB/topics/debug_key_value.h>
#include <uORB/topics/sensor_combined.h> #include <uORB/topics/sensor_combined.h>
#include <uORB/topics/vehicle_attitude.h> #include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/parameter_update.h> #include <uORB/topics/parameter_update.h>
#include <drivers/drv_hrt.h> #include <drivers/drv_hrt.h>
@ -204,6 +205,8 @@ int attitude_estimator_ekf_thread_main(int argc, char *argv[])
memset(&raw, 0, sizeof(raw)); memset(&raw, 0, sizeof(raw));
struct vehicle_attitude_s att; struct vehicle_attitude_s att;
memset(&att, 0, sizeof(att)); memset(&att, 0, sizeof(att));
struct vehicle_status_s state;
memset(&state, 0, sizeof(state));
uint64_t last_data = 0; uint64_t last_data = 0;
uint64_t last_measurement = 0; uint64_t last_measurement = 0;
@ -216,6 +219,9 @@ int attitude_estimator_ekf_thread_main(int argc, char *argv[])
/* subscribe to param changes */ /* subscribe to param changes */
int sub_params = orb_subscribe(ORB_ID(parameter_update)); int sub_params = orb_subscribe(ORB_ID(parameter_update));
/* subscribe to system state*/
int sub_state = orb_subscribe(ORB_ID(vehicle_status));
/* advertise attitude */ /* advertise attitude */
orb_advert_t pub_att = orb_advertise(ORB_ID(vehicle_attitude), &att); orb_advert_t pub_att = orb_advertise(ORB_ID(vehicle_attitude), &att);
@ -226,13 +232,15 @@ int attitude_estimator_ekf_thread_main(int argc, char *argv[])
thread_running = true; thread_running = true;
/* advertise debug value */ /* advertise debug value */
struct debug_key_value_s dbg = { .key = "", .value = 0.0f }; // struct debug_key_value_s dbg = { .key = "", .value = 0.0f };
orb_advert_t pub_dbg = -1; // orb_advert_t pub_dbg = -1;
float sensor_update_hz[3] = {0.0f, 0.0f, 0.0f};
// XXX write this out to perf regs
/* keep track of sensor updates */ /* keep track of sensor updates */
uint32_t sensor_last_count[3] = {0, 0, 0}; uint32_t sensor_last_count[3] = {0, 0, 0};
uint64_t sensor_last_timestamp[3] = {0, 0, 0}; uint64_t sensor_last_timestamp[3] = {0, 0, 0};
float sensor_update_hz[3] = {0.0f, 0.0f, 0.0f};
struct attitude_estimator_ekf_params ekf_params; struct attitude_estimator_ekf_params ekf_params;
@ -259,8 +267,12 @@ int attitude_estimator_ekf_thread_main(int argc, char *argv[])
if (ret < 0) { if (ret < 0) {
/* XXX this is seriously bad - should be an emergency */ /* XXX this is seriously bad - should be an emergency */
} else if (ret == 0) { } else if (ret == 0) {
/* XXX this means no sensor data - should be critical or emergency */ /* check if we're in HIL - not getting sensor data is fine then */
printf("[attitude estimator ekf] WARNING: Not getting sensor data - sensor app running?\n"); orb_copy(ORB_ID(vehicle_status), sub_state, &state);
if (!state.flag_hil_enabled) {
fprintf(stderr,
"[att ekf] WARNING: Not getting sensors - sensor app running?\n");
}
} else { } else {
/* only update parameters if they changed */ /* only update parameters if they changed */
@ -347,9 +359,6 @@ int attitude_estimator_ekf_thread_main(int argc, char *argv[])
overloadcounter++; overloadcounter++;
} }
int32_t z_k_sizes = 9;
// float u[4] = {0.0f, 0.0f, 0.0f, 0.0f};
static bool const_initialized = false; static bool const_initialized = false;
/* initialize with good values once we have a reasonable dt estimate */ /* initialize with good values once we have a reasonable dt estimate */
@ -392,7 +401,7 @@ int attitude_estimator_ekf_thread_main(int argc, char *argv[])
continue; continue;
} }
uint64_t timing_diff = hrt_absolute_time() - timing_start; // uint64_t timing_diff = hrt_absolute_time() - timing_start;
// /* print rotation matrix every 200th time */ // /* print rotation matrix every 200th time */
if (printcounter % 200 == 0) { if (printcounter % 200 == 0) {

View File

@ -211,8 +211,9 @@ HIL::init()
if (ret != OK) if (ret != OK)
return ret; return ret;
/* try to claim the generic PWM output device node as well - it's OK if we fail at this */ // XXX already claimed with CDEV
ret = register_driver(PWM_OUTPUT_DEVICE_PATH, &fops, 0666, (void *)this); ///* try to claim the generic PWM output device node as well - it's OK if we fail at this */
//ret = register_driver(PWM_OUTPUT_DEVICE_PATH, &fops, 0666, (void *)this);
if (ret == OK) { if (ret == OK) {
log("default PWM output device"); log("default PWM output device");
_primary_pwm_device = true; _primary_pwm_device = true;
@ -221,11 +222,11 @@ HIL::init()
/* reset GPIOs */ /* reset GPIOs */
// gpio_reset(); // gpio_reset();
/* start the IO interface task */ /* start the HIL interface task */
_task = task_spawn("fmuservo", _task = task_spawn("fmuhil",
SCHED_DEFAULT, SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT, SCHED_PRIORITY_DEFAULT,
1024, 2048,
(main_t)&HIL::task_main_trampoline, (main_t)&HIL::task_main_trampoline,
nullptr); nullptr);

View File

@ -224,7 +224,7 @@ PX4FMU::init()
_task = task_spawn("fmuservo", _task = task_spawn("fmuservo",
SCHED_DEFAULT, SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT, SCHED_PRIORITY_DEFAULT,
1024, 2048,
(main_t)&PX4FMU::task_main_trampoline, (main_t)&PX4FMU::task_main_trampoline,
nullptr); nullptr);

View File

@ -218,8 +218,6 @@ handle_message(mavlink_message_t *msg)
if (msg->msgid == MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST) { 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_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); mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(msg, &quad_motors_setpoint);
//printf("got message\n");
//printf("got MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT target_system=%u, sysid = %u\n", mavlink_system.sysid, quad_motors_setpoint.mode);
if (mavlink_system.sysid < 4) { if (mavlink_system.sysid < 4) {
@ -276,61 +274,6 @@ handle_message(mavlink_message_t *msg)
/* Publish */ /* Publish */
orb_publish(ORB_ID(offboard_control_setpoint), offboard_control_sp_pub, &offboard_control_sp); orb_publish(ORB_ID(offboard_control_setpoint), offboard_control_sp_pub, &offboard_control_sp);
} }
// /* change armed status if required */
// bool cmd_armed = (quad_motors_setpoint.mode & MAVLINK_OFFBOARD_CONTROL_FLAG_ARMED);
// bool cmd_generated = false;
// if (v_status.flag_control_offboard_enabled != cmd_armed) {
// vcmd.param1 = cmd_armed;
// vcmd.param2 = 0;
// vcmd.param3 = 0;
// vcmd.param4 = 0;
// vcmd.param5 = 0;
// vcmd.param6 = 0;
// vcmd.param7 = 0;
// vcmd.command = MAV_CMD_COMPONENT_ARM_DISARM;
// vcmd.target_system = mavlink_system.sysid;
// vcmd.target_component = MAV_COMP_ID_ALL;
// vcmd.source_system = msg->sysid;
// vcmd.source_component = msg->compid;
// vcmd.confirmation = 1;
// cmd_generated = true;
// }
// /* check if input has to be enabled */
// if ((v_status.flag_control_rates_enabled != (quad_motors_setpoint.mode == MAVLINK_OFFBOARD_CONTROL_MODE_RATES)) ||
// (v_status.flag_control_attitude_enabled != (quad_motors_setpoint.mode == MAVLINK_OFFBOARD_CONTROL_MODE_ATTITUDE)) ||
// (v_status.flag_control_velocity_enabled != (quad_motors_setpoint.mode == MAVLINK_OFFBOARD_CONTROL_MODE_VELOCITY)) ||
// (v_status.flag_control_position_enabled != (quad_motors_setpoint.mode == MAVLINK_OFFBOARD_CONTROL_MODE_POSITION))) {
// vcmd.param1 = (quad_motors_setpoint.mode == MAVLINK_OFFBOARD_CONTROL_MODE_RATES);
// vcmd.param2 = (quad_motors_setpoint.mode == MAVLINK_OFFBOARD_CONTROL_MODE_ATTITUDE);
// vcmd.param3 = (quad_motors_setpoint.mode == MAVLINK_OFFBOARD_CONTROL_MODE_VELOCITY);
// vcmd.param4 = (quad_motors_setpoint.mode == MAVLINK_OFFBOARD_CONTROL_MODE_POSITION);
// vcmd.param5 = 0;
// vcmd.param6 = 0;
// vcmd.param7 = 0;
// vcmd.command = PX4_CMD_CONTROLLER_SELECTION;
// vcmd.target_system = mavlink_system.sysid;
// vcmd.target_component = MAV_COMP_ID_ALL;
// vcmd.source_system = msg->sysid;
// vcmd.source_component = msg->compid;
// vcmd.confirmation = 1;
// cmd_generated = true;
// }
// if (cmd_generated) {
// /* 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);
// }
// }
} }
} }
@ -342,8 +285,6 @@ handle_message(mavlink_message_t *msg)
* COMMAND_LONG message or a SET_MODE message * COMMAND_LONG message or a SET_MODE message
*/ */
// printf("\n HIL ENABLED?: %s \n",(mavlink_hil_enabled)?"true":"false");
if (mavlink_hil_enabled) { if (mavlink_hil_enabled) {
if (msg->msgid == MAVLINK_MSG_ID_HIL_STATE) { if (msg->msgid == MAVLINK_MSG_ID_HIL_STATE) {
@ -351,20 +292,6 @@ handle_message(mavlink_message_t *msg)
mavlink_hil_state_t hil_state; mavlink_hil_state_t hil_state;
mavlink_msg_hil_state_decode(msg, &hil_state); mavlink_msg_hil_state_decode(msg, &hil_state);
// printf("\n HILSTATE : \n LAT: %i \n LON: %i \n ALT: %i \n "
// "ROLL %i \n PITCH %i \n YAW %i \n"
// "ROLLSPEED: %i \n PITCHSPEED: %i \n, YAWSPEED: %i \n",
// hil_state.lat/1000000, // 1e7
// hil_state.lon/1000000, // 1e7
// hil_state.alt/1000, // mm
// hil_state.roll, // float rad
// hil_state.pitch, // float rad
// hil_state.yaw, // float rad
// hil_state.rollspeed, // float rad/s
// hil_state.pitchspeed, // float rad/s
// hil_state.yawspeed); // float rad/s
hil_global_pos.lat = hil_state.lat; hil_global_pos.lat = hil_state.lat;
hil_global_pos.lon = hil_state.lon; hil_global_pos.lon = hil_state.lon;
hil_global_pos.alt = hil_state.alt / 1000.0f; hil_global_pos.alt = hil_state.alt / 1000.0f;