forked from Archive/PX4-Autopilot
commit
00fc4b5f13
|
@ -104,7 +104,7 @@ static void fill_manual_control_sp_msg(struct manual_control_setpoint_s *manual,
|
|||
manual->z = man_msg->z / 1000.0f;
|
||||
}
|
||||
|
||||
void fill_sensors_from_imu_msg(struct sensor_combined_s *sensor, mavlink_hil_sensor_t *imu) {
|
||||
static void fill_sensors_from_imu_msg(struct sensor_combined_s *sensor, mavlink_hil_sensor_t *imu) {
|
||||
hrt_abstime timestamp = hrt_absolute_time();
|
||||
sensor->timestamp = timestamp;
|
||||
sensor->gyro_raw[0] = imu->xgyro * 1000.0f;
|
||||
|
|
|
@ -273,6 +273,7 @@ void px4_show_tasks()
|
|||
}
|
||||
|
||||
__BEGIN_DECLS
|
||||
const char *getprogname();
|
||||
const char *getprogname()
|
||||
{
|
||||
pthread_t pid = pthread_self();
|
||||
|
|
Loading…
Reference in New Issue