mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-23 14:07:34 +08:00
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:
@@ -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
|
||||
};
|
||||
|
||||
Reference in New Issue
Block a user