forked from Archive/PX4-Autopilot
Merge pull request #2647 from mcharleb/qurt-build-fixes
Fixes for posix-arm and qurt builds
This commit is contained in:
commit
8751355e2e
|
@ -49,7 +49,7 @@ MODULES += modules/dataman
|
|||
MODULES += modules/sdlog2
|
||||
MODULES += modules/simulator
|
||||
MODULES += modules/commander
|
||||
#MODULES += modules/controllib
|
||||
MODULES += modules/controllib
|
||||
|
||||
#
|
||||
# Libraries
|
||||
|
@ -63,6 +63,7 @@ MODULES += lib/conversion
|
|||
# Linux port
|
||||
#
|
||||
MODULES += platforms/posix/px4_layer
|
||||
MODULES += platforms/posix/work_queue
|
||||
|
||||
#
|
||||
# Unit tests
|
||||
|
|
|
@ -64,6 +64,7 @@ MODULES += lib/conversion
|
|||
# Linux port
|
||||
#
|
||||
MODULES += platforms/posix/px4_layer
|
||||
MODULES += platforms/posix/work_queue
|
||||
#MODULES += platforms/posix/drivers/accelsim
|
||||
#MODULES += platforms/posix/drivers/gyrosim
|
||||
#MODULES += platforms/posix/drivers/adcsim
|
||||
|
|
|
@ -63,6 +63,7 @@ MODULES += modules/uORB
|
|||
# Linux port
|
||||
#
|
||||
MODULES += platforms/posix/px4_layer
|
||||
MODULES += platforms/posix/work_queue
|
||||
#MODULES += platforms/posix/drivers/accelsim
|
||||
#MODULES += platforms/posix/drivers/gyrosim
|
||||
#MODULES += platforms/posix/drivers/adcsim
|
||||
|
|
|
@ -47,7 +47,7 @@ MODULES += modules/systemlib/mixer
|
|||
MODULES += modules/uORB
|
||||
#MODULES += modules/dataman
|
||||
#MODULES += modules/sdlog2
|
||||
MODULES += modules/simulator
|
||||
#MODULES += modules/simulator
|
||||
#MODULES += modules/commander
|
||||
|
||||
#
|
||||
|
|
|
@ -47,7 +47,6 @@
|
|||
#include <poll.h>
|
||||
#include <fcntl.h>
|
||||
#include <float.h>
|
||||
#include <termios.h>
|
||||
#include <errno.h>
|
||||
#include <limits.h>
|
||||
#include <math.h>
|
||||
|
|
|
@ -137,7 +137,6 @@ private:
|
|||
int _vehicle_status_sub; /**< vehicle status subscription */
|
||||
int _motor_limits_sub; /**< motor limits subscription */
|
||||
|
||||
orb_advert_t _att_sp_pub; /**< attitude setpoint publication */
|
||||
orb_advert_t _v_rates_sp_pub; /**< rate setpoint publication */
|
||||
orb_advert_t _actuators_0_pub; /**< attitude actuator controls publication */
|
||||
orb_advert_t _controller_status_pub; /**< controller status publication */
|
||||
|
@ -170,8 +169,6 @@ private:
|
|||
|
||||
math::Matrix<3, 3> _I; /**< identity matrix */
|
||||
|
||||
bool _reset_yaw_sp; /**< reset yaw setpoint flag */
|
||||
|
||||
struct {
|
||||
param_t roll_p;
|
||||
param_t roll_rate_p;
|
||||
|
@ -315,7 +312,6 @@ MulticopterAttitudeControl::MulticopterAttitudeControl() :
|
|||
_vehicle_status_sub(-1),
|
||||
|
||||
/* publications */
|
||||
_att_sp_pub(nullptr),
|
||||
_v_rates_sp_pub(nullptr),
|
||||
_actuators_0_pub(nullptr),
|
||||
_controller_status_pub(nullptr),
|
||||
|
|
|
@ -457,7 +457,7 @@ int16_t uORB::FastRpcChannel::get_bulk_data
|
|||
}
|
||||
|
||||
if (topic_count_to_return != *topic_count) {
|
||||
PX4_WARN("Not sending all topics: topics_to_return:[%d] topics_returning:[%d]", topic_count_to_return, *topic_count);
|
||||
PX4_WARN("Not sending all topics: topics_to_return:[%ld] topics_returning:[%ld]", topic_count_to_return, *topic_count);
|
||||
}
|
||||
|
||||
_QueueMutex.unlock();
|
||||
|
@ -539,7 +539,7 @@ int32_t uORB::FastRpcChannel::copy_data_to_buffer(int32_t src_index, uint8_t *ds
|
|||
|
||||
} else {
|
||||
PX4_WARN("Error coping the DataMsg to dst buffer, insuffienct space. ");
|
||||
PX4_WARN("... offset[%d] len[%d] data_msg_len[%d]",
|
||||
PX4_WARN("... offset[%ld] len[%ld] data_msg_len[%ld]",
|
||||
offset, dst_buffer_len, (field_data_offset - offset) + _DataMsgQueue[ src_index ]._Length);
|
||||
}
|
||||
|
||||
|
|
|
@ -46,8 +46,6 @@
|
|||
#include <fcntl.h>
|
||||
#include <string.h>
|
||||
#include <px4_config.h>
|
||||
#include <sys/prctl.h>
|
||||
#include <termios.h>
|
||||
#include <math.h>
|
||||
#include <float.h>
|
||||
#include <uORB/uORB.h>
|
||||
|
@ -187,11 +185,11 @@ int position_estimator_inav_main(int argc, char *argv[])
|
|||
return 1;
|
||||
}
|
||||
|
||||
#ifdef INAV_DEBUG
|
||||
static void write_debug_log(const char *msg, float dt, float x_est[2], float y_est[2], float z_est[2], float x_est_prev[2], float y_est_prev[2], float z_est_prev[2],
|
||||
float acc[3], float corr_gps[3][2], float w_xy_gps_p, float w_xy_gps_v, float corr_mocap[3][1], float w_mocap_p,
|
||||
float corr_vision[3][2], float w_xy_vision_p, float w_z_vision_p, float w_xy_vision_v)
|
||||
{
|
||||
return;
|
||||
FILE *f = fopen(PX4_ROOTFSDIR"/fs/microsd/inav.log", "a");
|
||||
|
||||
if (f) {
|
||||
|
@ -216,6 +214,9 @@ static void write_debug_log(const char *msg, float dt, float x_est[2], float y_e
|
|||
fsync(fileno(f));
|
||||
fclose(f);
|
||||
}
|
||||
#else
|
||||
#define write_debug_log(...)
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* main
|
||||
|
|
|
@ -210,8 +210,9 @@ private:
|
|||
_baro_pub(nullptr),
|
||||
_gyro_pub(nullptr),
|
||||
_mag_pub(nullptr),
|
||||
_initialized(false),
|
||||
_initialized(false)
|
||||
#ifndef __PX4_QURT
|
||||
,
|
||||
_rc_channels_pub(nullptr),
|
||||
_actuator_outputs_sub(-1),
|
||||
_vehicle_attitude_sub(-1),
|
||||
|
|
|
@ -0,0 +1,3 @@
|
|||
#ifdef __PX4_QURT
|
||||
#include <dspal_types.h>
|
||||
#endif
|
|
@ -54,6 +54,7 @@
|
|||
#include <string>
|
||||
|
||||
#include <px4_tasks.h>
|
||||
#include <px4_posix.h>
|
||||
|
||||
#define MAX_CMD_LEN 100
|
||||
|
||||
|
|
|
@ -12,8 +12,6 @@
|
|||
|
||||
#include <sys/timespec.h>
|
||||
|
||||
#define CLOCK_REALTIME 1
|
||||
|
||||
__BEGIN_DECLS
|
||||
|
||||
#if 0
|
||||
|
|
|
@ -41,10 +41,11 @@
|
|||
#include <nuttx/arch.h>
|
||||
#include <nuttx/wqueue.h>
|
||||
#include <nuttx/clock.h>
|
||||
#elif defined(__PX4_POSIX) || defined(__PX4_QURT)
|
||||
#elif defined(__PX4_POSIX)
|
||||
|
||||
#include <stdint.h>
|
||||
#include <queue.h>
|
||||
#include <px4_platform_types.h>
|
||||
|
||||
__BEGIN_DECLS
|
||||
|
||||
|
|
|
@ -278,7 +278,7 @@ void px4_show_tasks()
|
|||
for (idx=0; idx < PX4_MAX_TASKS; idx++)
|
||||
{
|
||||
if (taskmap[idx].isused) {
|
||||
PX4_INFO(" %-10s %lu", taskmap[idx].name.c_str(), taskmap[idx].pid);
|
||||
PX4_INFO(" %-10s %d", taskmap[idx].name.c_str(), taskmap[idx].pid);
|
||||
count++;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -96,7 +96,7 @@ int MuorbTestExample::DefaultTest()
|
|||
orb_publish(ORB_ID(pwm_input), pub_fd, &pwm);
|
||||
orb_publish(ORB_ID(sensor_combined), pub_sc, &sc);
|
||||
|
||||
sleep(1);
|
||||
usleep(1000000);
|
||||
++i;
|
||||
}
|
||||
|
||||
|
@ -194,6 +194,7 @@ int MuorbTestExample::FileReadTest()
|
|||
rc = PX4_ERROR;
|
||||
|
||||
} else {
|
||||
/*
|
||||
int i = 0;
|
||||
while( ( read = getline( &line, &len, fp ) ) != -1 )
|
||||
{
|
||||
|
@ -201,6 +202,7 @@ int MuorbTestExample::FileReadTest()
|
|||
PX4_INFO( "LineNum[%d] LineLength[%d]", i, len );
|
||||
PX4_INFO( "LineNum[%d] Line[%s]", i, line );
|
||||
}
|
||||
*/
|
||||
PX4_INFO("Successfully opened file [%s]", TEST_FILE_PATH);
|
||||
fclose(fp);
|
||||
|
||||
|
|
Loading…
Reference in New Issue