Merge pull request #76 from PX4/topics_cleanup

Cleaned up different uorb topics, cleaned up excessive stack sizes
This commit is contained in:
px4dev 2012-12-01 22:53:15 -08:00
commit d92827c54c
6 changed files with 12 additions and 8 deletions

View File

@ -735,7 +735,7 @@ int mavlink_main(int argc, char *argv[])
mavlink_task = task_spawn("mavlink",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
6000,
2048,
mavlink_thread_main,
(const char**)argv);
exit(0);

View File

@ -202,6 +202,8 @@ handle_message(mavlink_message_t *msg)
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;
@ -427,4 +429,4 @@ receive_start(int uart)
pthread_t thread;
pthread_create(&thread, &receiveloop_attr, receive_thread, &uart);
return thread;
}
}

View File

@ -731,8 +731,8 @@ uorb_receive_start(void)
pthread_attr_t uorb_attr;
pthread_attr_init(&uorb_attr);
/* Set stack size, needs more than 8000 bytes */
pthread_attr_setstacksize(&uorb_attr, 4096);
/* Set stack size, needs less than 2k */
pthread_attr_setstacksize(&uorb_attr, 2048);
pthread_t thread;
pthread_create(&thread, &uorb_attr, uorb_receive_thread, NULL);

View File

@ -54,6 +54,7 @@
#include <uORB/topics/vehicle_attitude_setpoint.h>
#include <uORB/topics/optical_flow.h>
#include <uORB/topics/actuator_outputs.h>
#include <uORB/topics/actuator_controls_effective.h>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/debug_key_value.h>

View File

@ -1147,7 +1147,7 @@ Sensors::start()
_sensors_task = task_spawn("sensors_task",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
6000, /* XXX may be excesssive */
2048,
(main_t)&Sensors::task_main_trampoline,
nullptr);

View File

@ -48,13 +48,14 @@
#include <stdint.h>
#include "../uORB.h"
#include "actuator_controls.h"
#define NUM_ACTUATOR_CONTROLS 8
#define NUM_ACTUATOR_CONTROL_GROUPS 4 /**< for sanity checking */
#define NUM_ACTUATOR_CONTROLS_EFFECTIVE NUM_ACTUATOR_CONTROLS
#define NUM_ACTUATOR_CONTROL_GROUPS_EFFECTIVE NUM_ACTUATOR_CONTROL_GROUPS /**< for sanity checking */
struct actuator_controls_effective_s {
uint64_t timestamp;
float control_effective[NUM_ACTUATOR_CONTROLS];
float control_effective[NUM_ACTUATOR_CONTROLS_EFFECTIVE];
};
/* actuator control sets; this list can be expanded as more controllers emerge */