forked from Archive/PX4-Autopilot
POSIX: px4_getpid() fix
Since the PX4 code uses both px4_task and pthread APIs, px4_getpid() must be save to call from either context. On posix, this means we have to always return the pthread ID. Reverted simulator change of pthread to px4_task There may have been side effects if this was build for a target that has process/task scoped file descriptors. It is now safe to call px4_getpid() from this pthread context with this change for the posix build for px4_getpid(). Signed-off-by: Mark Charlebois <charlebm@gmail.com>
This commit is contained in:
parent
75ef0e1709
commit
d66b6ea701
|
@ -39,6 +39,7 @@
|
|||
#include <px4_log.h>
|
||||
#include <px4_tasks.h>
|
||||
#include <px4_time.h>
|
||||
#include <pthread.h>
|
||||
#include <poll.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <errno.h>
|
||||
|
|
|
@ -276,7 +276,7 @@ private:
|
|||
void send_mavlink_message(const uint8_t msgid, const void *msg, uint8_t component_ID);
|
||||
void update_sensors(struct sensor_combined_s *sensor, mavlink_hil_sensor_t *imu);
|
||||
void update_gps(mavlink_hil_gps_t *gps_sim);
|
||||
static int sending_trampoline(int argc, char *argv[]);
|
||||
static void *sending_trampoline(void *);
|
||||
void send();
|
||||
#endif
|
||||
};
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
#include <termios.h>
|
||||
#include <px4_log.h>
|
||||
#include <px4_time.h>
|
||||
#include <px4_tasks.h>
|
||||
#include "simulator.h"
|
||||
#include "errno.h"
|
||||
#include <drivers/drv_pwm_output.h>
|
||||
|
@ -251,9 +250,9 @@ void Simulator::poll_actuators() {
|
|||
}
|
||||
}
|
||||
|
||||
int Simulator::sending_trampoline(int argv, char *argc[]) {
|
||||
void *Simulator::sending_trampoline(void *) {
|
||||
_instance->send();
|
||||
return 0;
|
||||
return 0; // why do I have to put this???
|
||||
}
|
||||
|
||||
void Simulator::send() {
|
||||
|
@ -327,6 +326,21 @@ void Simulator::updateSamples()
|
|||
return;
|
||||
}
|
||||
|
||||
// create a thread for sending data to the simulator
|
||||
pthread_t sender_thread;
|
||||
|
||||
// initialize threads
|
||||
pthread_attr_t sender_thread_attr;
|
||||
pthread_attr_init(&sender_thread_attr);
|
||||
pthread_attr_setstacksize(&sender_thread_attr, 1000);
|
||||
|
||||
struct sched_param param;
|
||||
(void)pthread_attr_getschedparam(&sender_thread_attr, ¶m);
|
||||
|
||||
/* low priority */
|
||||
param.sched_priority = SCHED_PRIORITY_DEFAULT;
|
||||
(void)pthread_attr_setschedparam(&sender_thread_attr, ¶m);
|
||||
|
||||
// setup serial connection to autopilot (used to get manual controls)
|
||||
int serial_fd = openUart(PIXHAWK_DEVICE, 115200);
|
||||
|
||||
|
@ -367,15 +381,9 @@ void Simulator::updateSamples()
|
|||
// subscribe to topics
|
||||
_actuator_outputs_sub = orb_subscribe_multi(ORB_ID(actuator_outputs), 0);
|
||||
|
||||
char * argv[2] = { nullptr, nullptr };
|
||||
|
||||
// got data from simulator, now activate the sending thread
|
||||
px4_task_spawn_cmd("simulator-send",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_DEFAULT,
|
||||
1000,
|
||||
(px4_main_t)&Simulator::sending_trampoline,
|
||||
(char *const *)argv);
|
||||
pthread_create(&sender_thread, &sender_thread_attr, Simulator::sending_trampoline, NULL);
|
||||
pthread_attr_destroy(&sender_thread_attr);
|
||||
|
||||
// wait for new mavlink messages to arrive
|
||||
while (true) {
|
||||
|
|
|
@ -114,7 +114,7 @@ private:
|
|||
uint8_t *_data; /**< allocated object buffer */
|
||||
hrt_abstime _last_update; /**< time the object was last updated */
|
||||
volatile unsigned _generation; /**< object generation count */
|
||||
pid_t _publisher; /**< if nonzero, current publisher */
|
||||
unsigned long _publisher; /**< if nonzero, current publisher */
|
||||
const int _priority; /**< priority of topic */
|
||||
|
||||
SubscriberData *filp_to_sd(device::file_t *filp);
|
||||
|
|
|
@ -278,21 +278,9 @@ void px4_show_tasks()
|
|||
|
||||
__BEGIN_DECLS
|
||||
|
||||
int px4_getpid()
|
||||
unsigned long px4_getpid()
|
||||
{
|
||||
pthread_t pid = pthread_self();
|
||||
|
||||
if (pid == _shell_task_id)
|
||||
return SHELL_TASK_ID;
|
||||
|
||||
// Get pthread ID from the opaque ID
|
||||
for (int i=0; i<PX4_MAX_TASKS; ++i) {
|
||||
if (taskmap[i].isused && taskmap[i].pid == pid) {
|
||||
return i;
|
||||
}
|
||||
}
|
||||
PX4_ERR("px4_getpid() called from unknown thread context!");
|
||||
return -EINVAL;
|
||||
return (unsigned long)pthread_self();
|
||||
}
|
||||
|
||||
const char *getprogname();
|
||||
|
|
|
@ -99,7 +99,7 @@ __EXPORT int px4_ioctl(int fd, int cmd, unsigned long arg);
|
|||
__EXPORT int px4_poll(px4_pollfd_struct_t *fds, nfds_t nfds, int timeout);
|
||||
__EXPORT int px4_fsync(int fd);
|
||||
__EXPORT int px4_access(const char *pathname, int mode);
|
||||
__EXPORT int px4_getpid(void);
|
||||
__EXPORT unsigned long px4_getpid(void);
|
||||
|
||||
__END_DECLS
|
||||
#else
|
||||
|
|
Loading…
Reference in New Issue