diff options
Diffstat (limited to 'src/drivers/px4io/px4io.cpp')
-rw-r--r-- | src/drivers/px4io/px4io.cpp | 85 |
1 files changed, 66 insertions, 19 deletions
diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 8458c2fdb..972f45148 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -529,6 +529,11 @@ PX4IO::~PX4IO() if (_interface != nullptr) delete _interface; + /* deallocate perfs */ + perf_free(_perf_update); + perf_free(_perf_write); + perf_free(_perf_chan_count); + g_dev = nullptr; } @@ -576,8 +581,10 @@ PX4IO::init() ASSERT(_task == -1); sys_restart_param = param_find("SYS_RESTART_TYPE"); - /* Indicate restart type is unknown */ - param_set(sys_restart_param, &sys_restart_val); + if (sys_restart_param != PARAM_INVALID) { + /* Indicate restart type is unknown */ + param_set(sys_restart_param, &sys_restart_val); + } /* do regular cdev init */ ret = CDev::init(); @@ -683,6 +690,25 @@ PX4IO::init() /* send command to arm system via command API */ vehicle_command_s cmd; + /* send this to itself */ + param_t sys_id_param = param_find("MAV_SYS_ID"); + param_t comp_id_param = param_find("MAV_COMP_ID"); + + int32_t sys_id; + int32_t comp_id; + + if (param_get(sys_id_param, &sys_id)) { + errx(1, "PRM SYSID"); + } + + if (param_get(comp_id_param, &comp_id)) { + errx(1, "PRM CMPID"); + } + + cmd.target_system = sys_id; + cmd.target_component = comp_id; + cmd.source_system = sys_id; + cmd.source_component = comp_id; /* request arming */ cmd.param1 = 1.0f; cmd.param2 = 0; @@ -692,10 +718,7 @@ PX4IO::init() cmd.param6 = 0; cmd.param7 = 0; cmd.command = VEHICLE_CMD_COMPONENT_ARM_DISARM; - // cmd.target_system = status.system_id; - // cmd.target_component = status.component_id; - // cmd.source_system = status.system_id; - // cmd.source_component = status.component_id; + /* ask to confirm command */ cmd.confirmation = 1; @@ -773,7 +796,12 @@ PX4IO::init() } /* start the IO interface task */ - _task = task_create("px4io", SCHED_PRIORITY_ACTUATOR_OUTPUTS, 2048, (main_t)&PX4IO::task_main_trampoline, nullptr); + _task = task_spawn_cmd("px4io", + SCHED_DEFAULT, + SCHED_PRIORITY_ACTUATOR_OUTPUTS, + 2000, + (main_t)&PX4IO::task_main_trampoline, + nullptr); if (_task < 0) { debug("task start failed: %d", errno); @@ -968,13 +996,17 @@ PX4IO::task_main() int32_t failsafe_param_val; param_t failsafe_param = param_find("RC_FAILS_THR"); - if (failsafe_param > 0) { + if (failsafe_param != PARAM_INVALID) { param_get(failsafe_param, &failsafe_param_val); - uint16_t failsafe_thr = failsafe_param_val; - pret = io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_RC_THR_FAILSAFE_US, &failsafe_thr, 1); - if (pret != OK) { - log("failsafe upload failed"); + + if (failsafe_param_val > 0) { + + uint16_t failsafe_thr = failsafe_param_val; + pret = io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_RC_THR_FAILSAFE_US, &failsafe_thr, 1); + if (pret != OK) { + log("failsafe upload failed, FS: %d us", (int)failsafe_thr); + } } } @@ -1432,7 +1464,7 @@ PX4IO::io_get_raw_rc_input(rc_input_values &input_rc) /* we don't have the status bits, so input_source has to be set elsewhere */ input_rc.input_source = RC_INPUT_SOURCE_UNKNOWN; - static const unsigned prolog = (PX4IO_P_RAW_RC_BASE - PX4IO_P_RAW_RC_COUNT); + const unsigned prolog = (PX4IO_P_RAW_RC_BASE - PX4IO_P_RAW_RC_COUNT); uint16_t regs[RC_INPUT_MAX_CHANNELS + prolog]; /* @@ -1440,8 +1472,6 @@ PX4IO::io_get_raw_rc_input(rc_input_values &input_rc) * * This should be the common case (9 channel R/C control being a reasonable upper bound). */ - input_rc.timestamp_publication = hrt_absolute_time(); - ret = io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_RC_COUNT, ®s[0], prolog + 9); if (ret != OK) @@ -1453,23 +1483,38 @@ PX4IO::io_get_raw_rc_input(rc_input_values &input_rc) */ channel_count = regs[PX4IO_P_RAW_RC_COUNT]; - if (channel_count != _rc_chan_count) + /* limit the channel count */ + if (channel_count > RC_INPUT_MAX_CHANNELS) { + channel_count = RC_INPUT_MAX_CHANNELS; + } + + /* count channel count changes to identify signal integrity issues */ + if (channel_count != _rc_chan_count) { perf_count(_perf_chan_count); + } _rc_chan_count = channel_count; + input_rc.timestamp_publication = hrt_absolute_time(); + input_rc.rc_ppm_frame_length = regs[PX4IO_P_RAW_RC_DATA]; input_rc.rssi = regs[PX4IO_P_RAW_RC_NRSSI]; input_rc.rc_failsafe = (regs[PX4IO_P_RAW_RC_FLAGS] & PX4IO_P_RAW_RC_FLAGS_FAILSAFE); + input_rc.rc_lost = !(regs[PX4IO_P_RAW_RC_FLAGS] & PX4IO_P_RAW_RC_FLAGS_RC_OK); input_rc.rc_lost_frame_count = regs[PX4IO_P_RAW_LOST_FRAME_COUNT]; input_rc.rc_total_frame_count = regs[PX4IO_P_RAW_FRAME_COUNT]; + input_rc.channel_count = channel_count; /* rc_lost has to be set before the call to this function */ - if (!input_rc.rc_lost && !input_rc.rc_failsafe) + if (!input_rc.rc_lost && !input_rc.rc_failsafe) { _rc_last_valid = input_rc.timestamp_publication; + } input_rc.timestamp_last_signal = _rc_last_valid; + /* FIELDS NOT SET HERE */ + /* input_rc.input_source is set after this call XXX we might want to mirror the flags in the RC struct */ + if (channel_count > 9) { ret = io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_RC_BASE + 9, ®s[prolog + 9], channel_count - 9); @@ -1477,8 +1522,10 @@ PX4IO::io_get_raw_rc_input(rc_input_values &input_rc) return ret; } - input_rc.channel_count = channel_count; - memcpy(input_rc.values, ®s[prolog], channel_count * 2); + /* last thing set are the actual channel values as 16 bit values */ + for (unsigned i = 0; i < channel_count; i++) { + input_rc.values[i] = regs[prolog + i]; + } return ret; } |