int user_start(int argc, char *argv[]) { /* configure the first 8 PWM outputs (i.e. all of them) */ up_pwm_servo_init(0xff); /* run C++ ctors before we go any further */ up_cxxinitialize(); /* reset all to zero */ memset(&system_state, 0, sizeof(system_state)); /* configure the high-resolution time/callout interface */ hrt_init(); /* calculate our fw CRC so FMU can decide if we need to update */ calculate_fw_crc(); /* * Poll at 1ms intervals for received bytes that have not triggered * a DMA event. */ #ifdef CONFIG_ARCH_DMA hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)stm32_serial_dma_poll, NULL); #endif /* print some startup info */ lowsyslog("\nPX4IO: starting\n"); /* default all the LEDs to off while we start */ LED_AMBER(false); LED_BLUE(false); LED_SAFETY(false); #ifdef GPIO_LED4 LED_RING(false); #endif /* turn on servo power (if supported) */ #ifdef POWER_SERVO POWER_SERVO(true); #endif /* turn off S.Bus out (if supported) */ #ifdef ENABLE_SBUS_OUT ENABLE_SBUS_OUT(false); #endif /* start the safety switch handler */ safety_init(); /* initialise the control inputs */ controls_init(); /* set up the ADC */ adc_init(); /* start the FMU interface */ interface_init(); /* add a performance counter for mixing */ perf_counter_t mixer_perf = perf_alloc(PC_ELAPSED, "mix"); /* add a performance counter for controls */ perf_counter_t controls_perf = perf_alloc(PC_ELAPSED, "controls"); /* and one for measuring the loop rate */ perf_counter_t loop_perf = perf_alloc(PC_INTERVAL, "loop"); struct mallinfo minfo = mallinfo(); lowsyslog("MEM: free %u, largest %u\n", minfo.mxordblk, minfo.fordblks); /* initialize PWM limit lib */ pwm_limit_init(&pwm_limit); /* * P O L I C E L I G H T S * * Not enough memory, lock down. * * We might need to allocate mixers later, and this will * ensure that a developer doing a change will notice * that he just burned the remaining RAM with static * allocations. We don't want him to be able to * get past that point. This needs to be clearly * documented in the dev guide. * */ if (minfo.mxordblk < 600) { lowsyslog("ERR: not enough MEM"); bool phase = false; while (true) { if (phase) { LED_AMBER(true); LED_BLUE(false); } else { LED_AMBER(false); LED_BLUE(true); } up_udelay(250000); phase = !phase; } } /* Start the failsafe led init */ failsafe_led_init(); /* * Run everything in a tight loop. */ uint64_t last_debug_time = 0; uint64_t last_heartbeat_time = 0; for (;;) { /* track the rate at which the loop is running */ perf_count(loop_perf); /* kick the mixer */ perf_begin(mixer_perf); mixer_tick(); perf_end(mixer_perf); /* kick the control inputs */ perf_begin(controls_perf); controls_tick(); perf_end(controls_perf); if ((hrt_absolute_time() - last_heartbeat_time) > 250 * 1000) { last_heartbeat_time = hrt_absolute_time(); heartbeat_blink(); } ring_blink(); check_reboot(); /* check for debug activity (default: none) */ show_debug_messages(); /* post debug state at ~1Hz - this is via an auxiliary serial port * DEFAULTS TO OFF! */ if (hrt_absolute_time() - last_debug_time > (1000 * 1000)) { isr_debug(1, "d:%u s=0x%x a=0x%x f=0x%x m=%u", (unsigned)r_page_setup[PX4IO_P_SETUP_SET_DEBUG], (unsigned)r_status_flags, (unsigned)r_setup_arming, (unsigned)r_setup_features, (unsigned)mallinfo().mxordblk); last_debug_time = hrt_absolute_time(); } } }
/** * Transition from one hil state to another */ int hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd) { bool valid_transition = false; int ret = ERROR; if (current_status->hil_state == new_state) { valid_transition = true; } else { switch (new_state) { case HIL_STATE_OFF: /* we're in HIL and unexpected things can happen if we disable HIL now */ mavlink_log_critical(mavlink_fd, "Not switching off HIL (safety)"); valid_transition = false; break; case HIL_STATE_ON: if (current_status->arming_state == ARMING_STATE_INIT || current_status->arming_state == ARMING_STATE_STANDBY || current_status->arming_state == ARMING_STATE_STANDBY_ERROR) { mavlink_log_critical(mavlink_fd, "Switched to ON hil state"); valid_transition = true; // Disable publication of all attached sensors /* list directory */ DIR *d; d = opendir("/dev"); if (d) { struct dirent *direntry; char devname[24]; while ((direntry = readdir(d)) != NULL) { /* skip serial ports */ if (!strncmp("tty", direntry->d_name, 3)) { continue; } /* skip mtd devices */ if (!strncmp("mtd", direntry->d_name, 3)) { continue; } /* skip ram devices */ if (!strncmp("ram", direntry->d_name, 3)) { continue; } /* skip MMC devices */ if (!strncmp("mmc", direntry->d_name, 3)) { continue; } /* skip mavlink */ if (!strcmp("mavlink", direntry->d_name)) { continue; } /* skip console */ if (!strcmp("console", direntry->d_name)) { continue; } /* skip null */ if (!strcmp("null", direntry->d_name)) { continue; } snprintf(devname, sizeof(devname), "/dev/%s", direntry->d_name); int sensfd = ::open(devname, 0); if (sensfd < 0) { warn("failed opening device %s", devname); continue; } int block_ret = ::ioctl(sensfd, DEVIOCSPUBBLOCK, 1); close(sensfd); printf("Disabling %s: %s\n", devname, (block_ret == OK) ? "OK" : "ERROR"); } closedir(d); } else { /* failed opening dir */ warnx("FAILED LISTING DEVICE ROOT DIRECTORY"); return 1; } } break; default: warnx("Unknown hil state"); break; } } if (valid_transition) { current_status->hil_state = new_state; current_status->timestamp = hrt_absolute_time(); orb_publish(ORB_ID(vehicle_status), status_pub, current_status); // XXX also set lockdown here ret = OK; } else { mavlink_log_critical(mavlink_fd, "REJECTING invalid hil state transition"); } return ret; }
void Standard::update_vtol_state() { parameters_update(); /* After flipping the switch the vehicle will start the pusher (or tractor) motor, picking up * forward speed. After the vehicle has picked up enough speed the rotors shutdown. * For the back transition the pusher motor is immediately stopped and rotors reactivated. */ if (!_attc->is_fixed_wing_requested()) { // the transition to fw mode switch is off if (_vtol_schedule.flight_mode == MC_MODE) { // in mc mode _vtol_schedule.flight_mode = MC_MODE; _mc_roll_weight = 1.0f; _mc_pitch_weight = 1.0f; _mc_yaw_weight = 1.0f; _mc_throttle_weight = 1.0f; } else if (_vtol_schedule.flight_mode == FW_MODE) { // transition to mc mode if (_vtol_vehicle_status->vtol_transition_failsafe == true) { // Failsafe event, engage mc motors immediately _vtol_schedule.flight_mode = MC_MODE; _flag_enable_mc_motors = true; } else { // Regular backtransition _vtol_schedule.flight_mode = TRANSITION_TO_MC; _flag_enable_mc_motors = true; _vtol_schedule.transition_start = hrt_absolute_time(); } } else if (_vtol_schedule.flight_mode == TRANSITION_TO_FW) { // failsafe back to mc mode _vtol_schedule.flight_mode = MC_MODE; _mc_roll_weight = 1.0f; _mc_pitch_weight = 1.0f; _mc_yaw_weight = 1.0f; _mc_throttle_weight = 1.0f; } else if (_vtol_schedule.flight_mode == TRANSITION_TO_MC) { // transition to MC mode if transition time has passed // XXX: base this on XY hold velocity of MC if (hrt_elapsed_time(&_vtol_schedule.transition_start) > (_params_standard.back_trans_dur * 1000000.0f)) { _vtol_schedule.flight_mode = MC_MODE; } } // the pusher motor should never be powered when in or transitioning to mc mode _pusher_throttle = 0.0f; } else { // the transition to fw mode switch is on if (_vtol_schedule.flight_mode == MC_MODE) { // start transition to fw mode _vtol_schedule.flight_mode = TRANSITION_TO_FW; _vtol_schedule.transition_start = hrt_absolute_time(); } else if (_vtol_schedule.flight_mode == FW_MODE) { // in fw mode _vtol_schedule.flight_mode = FW_MODE; _mc_roll_weight = 0.0f; _mc_pitch_weight = 0.0f; _mc_yaw_weight = 0.0f; _mc_throttle_weight = 0.0f; } else if (_vtol_schedule.flight_mode == TRANSITION_TO_FW) { // continue the transition to fw mode while monitoring airspeed for a final switch to fw mode if (((_params_standard.airspeed_mode == control_state_s::AIRSPD_MODE_DISABLED || _airspeed->indicated_airspeed_m_s >= _params_standard.airspeed_trans) && (float)hrt_elapsed_time(&_vtol_schedule.transition_start) > (_params_standard.front_trans_time_min * 1000000.0f)) || can_transition_on_ground()) { _vtol_schedule.flight_mode = FW_MODE; // we can turn off the multirotor motors now _flag_enable_mc_motors = false; // don't set pusher throttle here as it's being ramped up elsewhere _trans_finished_ts = hrt_absolute_time(); } } else if (_vtol_schedule.flight_mode == TRANSITION_TO_MC) { // transitioning to mc mode & transition switch on - failsafe back into fw mode _vtol_schedule.flight_mode = FW_MODE; } } // map specific control phases to simple control modes switch (_vtol_schedule.flight_mode) { case MC_MODE: _vtol_mode = ROTARY_WING; break; case FW_MODE: _vtol_mode = FIXED_WING; break; case TRANSITION_TO_FW: case TRANSITION_TO_MC: _vtol_mode = TRANSITION; break; } }
void MavlinkParametersManager::handle_message(const mavlink_message_t *msg) { switch (msg->msgid) { case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: { /* request all parameters */ mavlink_param_request_list_t req_list; mavlink_msg_param_request_list_decode(msg, &req_list); if (req_list.target_system == mavlink_system.sysid && (req_list.target_component == mavlink_system.compid || req_list.target_component == MAV_COMP_ID_ALL)) { if (_send_all_index < 0) { _send_all_index = PARAM_HASH; } else { /* a restart should skip the hash check on the ground */ _send_all_index = 0; } } if (req_list.target_system == mavlink_system.sysid && req_list.target_component < 127 && (req_list.target_component != mavlink_system.compid || req_list.target_component == MAV_COMP_ID_ALL)) { // publish list request to UAVCAN driver via uORB. uavcan_parameter_request_s req; req.message_type = msg->msgid; req.node_id = req_list.target_component; req.param_index = 0; if (_uavcan_parameter_request_pub == nullptr) { _uavcan_parameter_request_pub = orb_advertise(ORB_ID(uavcan_parameter_request), &req); } else { orb_publish(ORB_ID(uavcan_parameter_request), _uavcan_parameter_request_pub, &req); } } break; } case MAVLINK_MSG_ID_PARAM_SET: { /* set parameter */ mavlink_param_set_t set; mavlink_msg_param_set_decode(msg, &set); if (set.target_system == mavlink_system.sysid && (set.target_component == mavlink_system.compid || set.target_component == MAV_COMP_ID_ALL)) { /* local name buffer to enforce null-terminated string */ char name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN + 1]; strncpy(name, set.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN); /* enforce null termination */ name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN] = '\0'; /* Whatever the value is, we're being told to stop sending */ if (strncmp(name, "_HASH_CHECK", sizeof(name)) == 0) { _send_all_index = -1; /* No other action taken, return */ return; } /* attempt to find parameter, set and send it */ param_t param = param_find_no_notification(name); if (param == PARAM_INVALID) { char buf[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN]; sprintf(buf, "[pm] unknown param: %s", name); _mavlink->send_statustext_info(buf); } else { // Load current value before setting it float curr_val; param_get(param, &curr_val); param_set(param, &(set.param_value)); // Check if the parameter changed. If it didn't change, send current value back if (!(fabsf(curr_val - set.param_value) > 0.0f)) { send_param(param); } } } if (set.target_system == mavlink_system.sysid && set.target_component < 127 && (set.target_component != mavlink_system.compid || set.target_component == MAV_COMP_ID_ALL)) { // publish set request to UAVCAN driver via uORB. uavcan_parameter_request_s req; req.message_type = msg->msgid; req.node_id = set.target_component; req.param_index = -1; strncpy(req.param_id, set.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN + 1); req.param_id[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN] = '\0'; if (set.param_type == MAV_PARAM_TYPE_REAL32) { req.param_type = MAV_PARAM_TYPE_REAL32; req.real_value = set.param_value; } else { int32_t val; memcpy(&val, &set.param_value, sizeof(int32_t)); req.param_type = MAV_PARAM_TYPE_INT64; req.int_value = val; } if (_uavcan_parameter_request_pub == nullptr) { _uavcan_parameter_request_pub = orb_advertise(ORB_ID(uavcan_parameter_request), &req); } else { orb_publish(ORB_ID(uavcan_parameter_request), _uavcan_parameter_request_pub, &req); } } break; } case MAVLINK_MSG_ID_PARAM_REQUEST_READ: { /* request one parameter */ mavlink_param_request_read_t req_read; mavlink_msg_param_request_read_decode(msg, &req_read); if (req_read.target_system == mavlink_system.sysid && (req_read.target_component == mavlink_system.compid || req_read.target_component == MAV_COMP_ID_ALL)) { /* when no index is given, loop through string ids and compare them */ if (req_read.param_index < 0) { /* XXX: I left this in so older versions of QGC wouldn't break */ if (strncmp(req_read.param_id, HASH_PARAM, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN) == 0) { /* return hash check for cached params */ uint32_t hash = param_hash_check(); /* build the one-off response message */ mavlink_param_value_t param_value; param_value.param_count = param_count_used(); param_value.param_index = -1; strncpy(param_value.param_id, HASH_PARAM, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN); param_value.param_type = MAV_PARAM_TYPE_UINT32; memcpy(¶m_value.param_value, &hash, sizeof(hash)); mavlink_msg_param_value_send_struct(_mavlink->get_channel(), ¶m_value); } else { /* local name buffer to enforce null-terminated string */ char name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN + 1]; strncpy(name, req_read.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN); /* enforce null termination */ name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN] = '\0'; /* attempt to find parameter and send it */ send_param(param_find_no_notification(name)); } } else { /* when index is >= 0, send this parameter again */ int ret = send_param(param_for_used_index(req_read.param_index)); if (ret == 1) { char buf[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN]; sprintf(buf, "[pm] unknown param ID: %u", req_read.param_index); _mavlink->send_statustext_info(buf); } else if (ret == 2) { char buf[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN]; sprintf(buf, "[pm] failed loading param from storage ID: %u", req_read.param_index); _mavlink->send_statustext_info(buf); } } } if (req_read.target_system == mavlink_system.sysid && req_read.target_component < 127 && (req_read.target_component != mavlink_system.compid || req_read.target_component == MAV_COMP_ID_ALL)) { // publish set request to UAVCAN driver via uORB. uavcan_parameter_request_s req = {}; req.timestamp = hrt_absolute_time(); req.message_type = msg->msgid; req.node_id = req_read.target_component; req.param_index = req_read.param_index; strncpy(req.param_id, req_read.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN + 1); req.param_id[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN] = '\0'; // Enque the request and forward the first to the uavcan node enque_uavcan_request(&req); request_next_uavcan_parameter(); } break; } case MAVLINK_MSG_ID_PARAM_MAP_RC: { /* map a rc channel to a parameter */ mavlink_param_map_rc_t map_rc; mavlink_msg_param_map_rc_decode(msg, &map_rc); if (map_rc.target_system == mavlink_system.sysid && (map_rc.target_component == mavlink_system.compid || map_rc.target_component == MAV_COMP_ID_ALL)) { /* Copy values from msg to uorb using the parameter_rc_channel_index as index */ size_t i = map_rc.parameter_rc_channel_index; _rc_param_map.param_index[i] = map_rc.param_index; strncpy(&(_rc_param_map.param_id[i * (rc_parameter_map_s::PARAM_ID_LEN + 1)]), map_rc.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN); /* enforce null termination */ _rc_param_map.param_id[i * (rc_parameter_map_s::PARAM_ID_LEN + 1) + rc_parameter_map_s::PARAM_ID_LEN] = '\0'; _rc_param_map.scale[i] = map_rc.scale; _rc_param_map.value0[i] = map_rc.param_value0; _rc_param_map.value_min[i] = map_rc.param_value_min; _rc_param_map.value_max[i] = map_rc.param_value_max; if (map_rc.param_index == -2) { // -2 means unset map _rc_param_map.valid[i] = false; } else { _rc_param_map.valid[i] = true; } _rc_param_map.timestamp = hrt_absolute_time(); if (_rc_param_map_pub == nullptr) { _rc_param_map_pub = orb_advertise(ORB_ID(rc_parameter_map), &_rc_param_map); } else { orb_publish(ORB_ID(rc_parameter_map), _rc_param_map_pub, &_rc_param_map); } } break; } default: break; } }
static void handle_message(mavlink_message_t *msg) { if (msg->msgid == MAVLINK_MSG_ID_COMMAND_LONG) { mavlink_command_long_t cmd_mavlink; mavlink_msg_command_long_decode(msg, &cmd_mavlink); if (cmd_mavlink.target_system == mavlink_system.sysid && ((cmd_mavlink.target_component == mavlink_system.compid) || (cmd_mavlink.target_component == MAV_COMP_ID_ALL))) { //check for MAVLINK terminate command if (cmd_mavlink.command == MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN && ((int)cmd_mavlink.param1) == 3) { /* This is the link shutdown command, terminate mavlink */ printf("[mavlink] Terminating .. \n"); fflush(stdout); usleep(50000); /* terminate other threads and this thread */ thread_should_exit = true; } else { /* Copy the content of mavlink_command_long_t cmd_mavlink into command_t cmd */ vcmd.param1 = cmd_mavlink.param1; vcmd.param2 = cmd_mavlink.param2; vcmd.param3 = cmd_mavlink.param3; vcmd.param4 = cmd_mavlink.param4; vcmd.param5 = cmd_mavlink.param5; vcmd.param6 = cmd_mavlink.param6; vcmd.param7 = cmd_mavlink.param7; vcmd.command = cmd_mavlink.command; vcmd.target_system = cmd_mavlink.target_system; vcmd.target_component = cmd_mavlink.target_component; vcmd.source_system = msg->sysid; vcmd.source_component = msg->compid; vcmd.confirmation = cmd_mavlink.confirmation; /* check if topic is advertised */ if (cmd_pub <= 0) { cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd); } /* publish */ orb_publish(ORB_ID(vehicle_command), cmd_pub, &vcmd); } } } if (msg->msgid == MAVLINK_MSG_ID_OPTICAL_FLOW) { mavlink_optical_flow_t flow; mavlink_msg_optical_flow_decode(msg, &flow); struct optical_flow_s f; f.timestamp = flow.time_usec; f.flow_raw_x = flow.flow_x; f.flow_raw_y = flow.flow_y; f.flow_comp_x_m = flow.flow_comp_m_x; f.flow_comp_y_m = flow.flow_comp_m_y; f.ground_distance_m = flow.ground_distance; f.quality = flow.quality; f.sensor_id = flow.sensor_id; /* check if topic is advertised */ if (flow_pub <= 0) { flow_pub = orb_advertise(ORB_ID(optical_flow), &f); } else { /* publish */ orb_publish(ORB_ID(optical_flow), flow_pub, &f); } } if (msg->msgid == MAVLINK_MSG_ID_SET_MODE) { /* Set mode on request */ mavlink_set_mode_t new_mode; mavlink_msg_set_mode_decode(msg, &new_mode); /* Copy the content of mavlink_command_long_t cmd_mavlink into command_t cmd */ vcmd.param1 = new_mode.base_mode; vcmd.param2 = new_mode.custom_mode; vcmd.param3 = 0; vcmd.param4 = 0; vcmd.param5 = 0; vcmd.param6 = 0; vcmd.param7 = 0; vcmd.command = MAV_CMD_DO_SET_MODE; vcmd.target_system = new_mode.target_system; vcmd.target_component = MAV_COMP_ID_ALL; vcmd.source_system = msg->sysid; vcmd.source_component = msg->compid; vcmd.confirmation = 1; /* check if topic is advertised */ if (cmd_pub <= 0) { cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd); } else { /* create command */ orb_publish(ORB_ID(vehicle_command), cmd_pub, &vcmd); } } /* Handle Vicon position estimates */ if (msg->msgid == MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE) { mavlink_vicon_position_estimate_t pos; mavlink_msg_vicon_position_estimate_decode(msg, &pos); vicon_position.timestamp = hrt_absolute_time(); vicon_position.x = pos.x; vicon_position.y = pos.y; vicon_position.z = pos.z; vicon_position.roll = pos.roll; vicon_position.pitch = pos.pitch; vicon_position.yaw = pos.yaw; if (vicon_position_pub <= 0) { vicon_position_pub = orb_advertise(ORB_ID(vehicle_vicon_position), &vicon_position); } else { orb_publish(ORB_ID(vehicle_vicon_position), vicon_position_pub, &vicon_position); } } /* Handle quadrotor motor setpoints */ if (msg->msgid == MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST) { mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t quad_motors_setpoint; mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(msg, &quad_motors_setpoint); if (mavlink_system.sysid < 4) { /* switch to a receiving link mode */ gcs_link = false; /* * rate control mode - defined by MAVLink */ uint8_t ml_mode = 0; bool ml_armed = false; switch (quad_motors_setpoint.mode) { case 0: ml_armed = false; break; case 1: ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_RATES; ml_armed = true; break; case 2: ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE; ml_armed = true; break; case 3: ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY; break; case 4: ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_POSITION; break; } offboard_control_sp.p1 = (float)quad_motors_setpoint.roll[mavlink_system.sysid - 1] / (float)INT16_MAX; offboard_control_sp.p2 = (float)quad_motors_setpoint.pitch[mavlink_system.sysid - 1] / (float)INT16_MAX; offboard_control_sp.p3 = (float)quad_motors_setpoint.yaw[mavlink_system.sysid - 1] / (float)INT16_MAX; offboard_control_sp.p4 = (float)quad_motors_setpoint.thrust[mavlink_system.sysid - 1] / (float)UINT16_MAX; if (quad_motors_setpoint.thrust[mavlink_system.sysid - 1] == 0) { ml_armed = false; } offboard_control_sp.armed = ml_armed; offboard_control_sp.mode = ml_mode; offboard_control_sp.timestamp = hrt_absolute_time(); /* check if topic has to be advertised */ if (offboard_control_sp_pub <= 0) { offboard_control_sp_pub = orb_advertise(ORB_ID(offboard_control_setpoint), &offboard_control_sp); } else { /* Publish */ orb_publish(ORB_ID(offboard_control_setpoint), offboard_control_sp_pub, &offboard_control_sp); } } } /* * Only decode hil messages in HIL mode. * * The HIL mode is enabled by the HIL bit flag * in the system mode. Either send a set mode * COMMAND_LONG message or a SET_MODE message */ if (mavlink_hil_enabled) { uint64_t timestamp = hrt_absolute_time(); if (msg->msgid == MAVLINK_MSG_ID_HIGHRES_IMU) { mavlink_highres_imu_t imu; mavlink_msg_highres_imu_decode(msg, &imu); /* packet counter */ static uint16_t hil_counter = 0; static uint16_t hil_frames = 0; static uint64_t old_timestamp = 0; /* sensors general */ hil_sensors.timestamp = hrt_absolute_time(); /* hil gyro */ static const float mrad2rad = 1.0e-3f; hil_sensors.gyro_counter = hil_counter; hil_sensors.gyro_raw[0] = imu.xgyro / mrad2rad; hil_sensors.gyro_raw[1] = imu.ygyro / mrad2rad; hil_sensors.gyro_raw[2] = imu.zgyro / mrad2rad; hil_sensors.gyro_rad_s[0] = imu.xgyro; hil_sensors.gyro_rad_s[1] = imu.ygyro; hil_sensors.gyro_rad_s[2] = imu.zgyro; /* accelerometer */ hil_sensors.accelerometer_counter = hil_counter; static const float mg2ms2 = 9.8f / 1000.0f; hil_sensors.accelerometer_raw[0] = imu.xacc / mg2ms2; hil_sensors.accelerometer_raw[1] = imu.yacc / mg2ms2; hil_sensors.accelerometer_raw[2] = imu.zacc / mg2ms2; hil_sensors.accelerometer_m_s2[0] = imu.xacc; hil_sensors.accelerometer_m_s2[1] = imu.yacc; hil_sensors.accelerometer_m_s2[2] = imu.zacc; hil_sensors.accelerometer_mode = 0; // TODO what is this? hil_sensors.accelerometer_range_m_s2 = 32.7f; // int16 /* adc */ hil_sensors.adc_voltage_v[0] = 0; hil_sensors.adc_voltage_v[1] = 0; hil_sensors.adc_voltage_v[2] = 0; /* magnetometer */ float mga2ga = 1.0e-3f; hil_sensors.magnetometer_counter = hil_counter; hil_sensors.magnetometer_raw[0] = imu.xmag / mga2ga; hil_sensors.magnetometer_raw[1] = imu.ymag / mga2ga; hil_sensors.magnetometer_raw[2] = imu.zmag / mga2ga; hil_sensors.magnetometer_ga[0] = imu.xmag; hil_sensors.magnetometer_ga[1] = imu.ymag; hil_sensors.magnetometer_ga[2] = imu.zmag; hil_sensors.magnetometer_range_ga = 32.7f; // int16 hil_sensors.magnetometer_mode = 0; // TODO what is this hil_sensors.magnetometer_cuttoff_freq_hz = 50.0f; /* baro */ hil_sensors.baro_pres_mbar = imu.abs_pressure; hil_sensors.baro_alt_meter = imu.pressure_alt; hil_sensors.baro_temp_celcius = imu.temperature; hil_sensors.gyro_counter = hil_counter; hil_sensors.magnetometer_counter = hil_counter; hil_sensors.accelerometer_counter = hil_counter; /* publish */ orb_publish(ORB_ID(sensor_combined), pub_hil_sensors, &hil_sensors); // increment counters hil_counter++; hil_frames++; // output if ((timestamp - old_timestamp) > 10000000) { printf("receiving hil imu at %d hz\n", hil_frames/10); old_timestamp = timestamp; hil_frames = 0; } } if (msg->msgid == MAVLINK_MSG_ID_GPS_RAW_INT) { mavlink_gps_raw_int_t gps; mavlink_msg_gps_raw_int_decode(msg, &gps); /* packet counter */ static uint16_t hil_counter = 0; static uint16_t hil_frames = 0; static uint64_t old_timestamp = 0; /* gps */ hil_gps.timestamp_position = gps.time_usec; hil_gps.time_gps_usec = gps.time_usec; hil_gps.lat = gps.lat; hil_gps.lon = gps.lon; hil_gps.alt = gps.alt; hil_gps.eph_m = (float)gps.eph * 1e-2f; // from cm to m hil_gps.epv_m = (float)gps.epv * 1e-2f; // from cm to m hil_gps.s_variance_m_s = 5.0f; hil_gps.p_variance_m = hil_gps.eph_m * hil_gps.eph_m; hil_gps.vel_m_s = (float)gps.vel * 1e-2f; // from cm/s to m/s /* gps.cog is in degrees 0..360 * 100, heading is -PI..+PI */ float heading_rad = gps.cog * M_DEG_TO_RAD_F * 1e-2f; /* go back to -PI..PI */ if (heading_rad > M_PI_F) heading_rad -= 2.0f * M_PI_F; hil_gps.vel_n_m_s = (float)gps.vel * 1e-2f * cosf(heading_rad); hil_gps.vel_e_m_s = (float)gps.vel * 1e-2f * sinf(heading_rad); hil_gps.vel_d_m_s = 0.0f; hil_gps.vel_ned_valid = true; /* COG (course over ground) is speced as -PI..+PI */ hil_gps.cog_rad = heading_rad; hil_gps.fix_type = gps.fix_type; hil_gps.satellites_visible = gps.satellites_visible; /* publish */ orb_publish(ORB_ID(vehicle_gps_position), pub_hil_gps, &hil_gps); // increment counters hil_counter += 1 ; hil_frames += 1 ; // output if ((timestamp - old_timestamp) > 10000000) { printf("receiving hil gps at %d hz\n", hil_frames/10); old_timestamp = timestamp; hil_frames = 0; } } if (msg->msgid == MAVLINK_MSG_ID_HIL_STATE) { mavlink_hil_state_t hil_state; mavlink_msg_hil_state_decode(msg, &hil_state); /* Calculate Rotation Matrix */ //TODO: better clarification which app does this, atm we have a ekf for quadrotors which does this, but there is no such thing if fly in fixed wing mode if (mavlink_system.type == MAV_TYPE_FIXED_WING) { //TODO: assuming low pitch and roll values for now hil_attitude.R[0][0] = cosf(hil_state.yaw); hil_attitude.R[0][1] = sinf(hil_state.yaw); hil_attitude.R[0][2] = 0.0f; hil_attitude.R[1][0] = -sinf(hil_state.yaw); hil_attitude.R[1][1] = cosf(hil_state.yaw); hil_attitude.R[1][2] = 0.0f; hil_attitude.R[2][0] = 0.0f; hil_attitude.R[2][1] = 0.0f; hil_attitude.R[2][2] = 1.0f; hil_attitude.R_valid = true; } hil_global_pos.lat = hil_state.lat; hil_global_pos.lon = hil_state.lon; hil_global_pos.alt = hil_state.alt / 1000.0f; hil_global_pos.vx = hil_state.vx / 100.0f; hil_global_pos.vy = hil_state.vy / 100.0f; hil_global_pos.vz = hil_state.vz / 100.0f; /* set timestamp and notify processes (broadcast) */ hil_global_pos.timestamp = hrt_absolute_time(); orb_publish(ORB_ID(vehicle_global_position), pub_hil_global_pos, &hil_global_pos); hil_attitude.roll = hil_state.roll; hil_attitude.pitch = hil_state.pitch; hil_attitude.yaw = hil_state.yaw; hil_attitude.rollspeed = hil_state.rollspeed; hil_attitude.pitchspeed = hil_state.pitchspeed; hil_attitude.yawspeed = hil_state.yawspeed; /* set timestamp and notify processes (broadcast) */ hil_attitude.timestamp = hrt_absolute_time(); orb_publish(ORB_ID(vehicle_attitude), pub_hil_attitude, &hil_attitude); } if (msg->msgid == MAVLINK_MSG_ID_MANUAL_CONTROL) { mavlink_manual_control_t man; mavlink_msg_manual_control_decode(msg, &man); struct rc_channels_s rc_hil; memset(&rc_hil, 0, sizeof(rc_hil)); static orb_advert_t rc_pub = 0; rc_hil.timestamp = hrt_absolute_time(); rc_hil.chan_count = 4; rc_hil.chan[0].scaled = man.x / 1000.0f; rc_hil.chan[1].scaled = man.y / 1000.0f; rc_hil.chan[2].scaled = man.r / 1000.0f; rc_hil.chan[3].scaled = man.z / 1000.0f; struct manual_control_setpoint_s mc; static orb_advert_t mc_pub = 0; int manual_sub = orb_subscribe(ORB_ID(manual_control_setpoint)); /* get a copy first, to prevent altering values that are not sent by the mavlink command */ orb_copy(ORB_ID(manual_control_setpoint), manual_sub, &mc); mc.timestamp = rc_hil.timestamp; mc.roll = man.x / 1000.0f; mc.pitch = man.y / 1000.0f; mc.yaw = man.r / 1000.0f; mc.throttle = man.z / 1000.0f; /* fake RC channels with manual control input from simulator */ if (rc_pub == 0) { rc_pub = orb_advertise(ORB_ID(rc_channels), &rc_hil); } else { orb_publish(ORB_ID(rc_channels), rc_pub, &rc_hil); } if (mc_pub == 0) { mc_pub = orb_advertise(ORB_ID(manual_control_setpoint), &mc); } else { orb_publish(ORB_ID(manual_control_setpoint), mc_pub, &mc); } } } }
void MavlinkMissionManager::handle_mission_count(const mavlink_message_t *msg) { mavlink_mission_count_t wpc; mavlink_msg_mission_count_decode(msg, &wpc); if (CHECK_SYSID_COMPID_MISSION(wpc)) { if (_state == MAVLINK_WPM_STATE_IDLE) { _time_last_recv = hrt_absolute_time(); if (_transfer_in_progress) { send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR); return; } _transfer_in_progress = true; if (wpc.count > _max_count) { if (_verbose) { warnx("WPM: MISSION_COUNT ERROR: too many waypoints (%d), supported: %d", wpc.count, _max_count); } send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_NO_SPACE); _transfer_in_progress = false; return; } if (wpc.count == 0) { if (_verbose) { warnx("WPM: MISSION_COUNT 0, clearing waypoints list and staying in state MAVLINK_WPM_STATE_IDLE"); } /* alternate dataman ID anyway to let navigator know about changes */ update_active_mission(_dataman_id == 0 ? 1 : 0, 0, 0); send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ACCEPTED); _transfer_in_progress = false; return; } if (_verbose) { warnx("WPM: MISSION_COUNT %u from ID %u, changing state to MAVLINK_WPM_STATE_GETLIST", wpc.count, msg->sysid); } _state = MAVLINK_WPM_STATE_GETLIST; _transfer_seq = 0; _transfer_partner_sysid = msg->sysid; _transfer_partner_compid = msg->compid; _transfer_count = wpc.count; _transfer_dataman_id = _dataman_id == 0 ? 1 : 0; // use inactive storage for transmission _transfer_current_seq = -1; } else if (_state == MAVLINK_WPM_STATE_GETLIST) { _time_last_recv = hrt_absolute_time(); if (_transfer_seq == 0) { /* looks like our MISSION_REQUEST was lost, try again */ if (_verbose) { warnx("WPM: MISSION_COUNT %u from ID %u (again)", wpc.count, msg->sysid); } _mavlink->send_statustext_info("WP CMD OK TRY AGAIN"); } else { if (_verbose) { warnx("WPM: MISSION_COUNT ERROR: busy, already receiving seq %u", _transfer_seq); } _mavlink->send_statustext_critical("WPM: REJ. CMD: Busy"); return; } } else { if (_verbose) { warnx("WPM: MISSION_COUNT ERROR: busy, state %i", _state); } _mavlink->send_statustext_critical("WPM: IGN MISSION_COUNT: Busy"); return; } send_mission_request(_transfer_partner_sysid, _transfer_partner_compid, _transfer_seq); } }
void controls_tick() { /* * Gather R/C control inputs from supported sources. * * Note that if you're silly enough to connect more than * one control input source, they're going to fight each * other. Don't do that. */ /* receive signal strenght indicator (RSSI). 0 = no connection, 255: perfect connection */ uint16_t rssi = 0; perf_begin(c_gather_dsm); uint16_t temp_count = r_raw_rc_count; bool dsm_updated = dsm_input(r_raw_rc_values, &temp_count); if (dsm_updated) { r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_DSM; r_raw_rc_count = temp_count & 0x7fff; if (temp_count & 0x8000) r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_DSM11; else r_status_flags &= ~PX4IO_P_STATUS_FLAGS_RC_DSM11; rssi = 255; } perf_end(c_gather_dsm); perf_begin(c_gather_sbus); bool sbus_updated = sbus_input(r_raw_rc_values, &r_raw_rc_count, &rssi, PX4IO_CONTROL_CHANNELS /* XXX this should be INPUT channels, once untangled */); if (sbus_updated) { r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_SBUS; } perf_end(c_gather_sbus); /* * XXX each S.bus frame will cause a PPM decoder interrupt * storm (lots of edges). It might be sensible to actually * disable the PPM decoder completely if we have S.bus signal. */ perf_begin(c_gather_ppm); bool ppm_updated = ppm_input(r_raw_rc_values, &r_raw_rc_count, &r_page_status[PX4IO_P_STATUS_RC_DATA]); if (ppm_updated) { /* XXX sample RSSI properly here */ rssi = 255; r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_PPM; } perf_end(c_gather_ppm); /* limit number of channels to allowable data size */ if (r_raw_rc_count > PX4IO_INPUT_CHANNELS) r_raw_rc_count = PX4IO_INPUT_CHANNELS; /* * In some cases we may have received a frame, but input has still * been lost. */ bool rc_input_lost = false; /* * If we received a new frame from any of the RC sources, process it. */ if (dsm_updated || sbus_updated || ppm_updated) { /* update RC-received timestamp */ system_state.rc_channels_timestamp = hrt_absolute_time(); /* record a bitmask of channels assigned */ unsigned assigned_channels = 0; /* map raw inputs to mapped inputs */ /* XXX mapping should be atomic relative to protocol */ for (unsigned i = 0; i < r_raw_rc_count; i++) { /* map the input channel */ uint16_t *conf = &r_page_rc_input_config[i * PX4IO_P_RC_CONFIG_STRIDE]; if (conf[PX4IO_P_RC_CONFIG_OPTIONS] & PX4IO_P_RC_CONFIG_OPTIONS_ENABLED) { uint16_t raw = r_raw_rc_values[i]; int16_t scaled; /* * 1) Constrain to min/max values, as later processing depends on bounds. */ if (raw < conf[PX4IO_P_RC_CONFIG_MIN]) raw = conf[PX4IO_P_RC_CONFIG_MIN]; if (raw > conf[PX4IO_P_RC_CONFIG_MAX]) raw = conf[PX4IO_P_RC_CONFIG_MAX]; /* * 2) Scale around the mid point differently for lower and upper range. * * This is necessary as they don't share the same endpoints and slope. * * First normalize to 0..1 range with correct sign (below or above center), * then scale to 20000 range (if center is an actual center, -10000..10000, * if parameters only support half range, scale to 10000 range, e.g. if * center == min 0..10000, if center == max -10000..0). * * As the min and max bounds were enforced in step 1), division by zero * cannot occur, as for the case of center == min or center == max the if * statement is mutually exclusive with the arithmetic NaN case. * * DO NOT REMOVE OR ALTER STEP 1! */ if (raw > (conf[PX4IO_P_RC_CONFIG_CENTER] + conf[PX4IO_P_RC_CONFIG_DEADZONE])) { scaled = 10000.0f * ((raw - conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE]) / (float)(conf[PX4IO_P_RC_CONFIG_MAX] - conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE])); } else if (raw < (conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE])) { scaled = 10000.0f * ((raw - conf[PX4IO_P_RC_CONFIG_CENTER] + conf[PX4IO_P_RC_CONFIG_DEADZONE]) / (float)(conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE] - conf[PX4IO_P_RC_CONFIG_MIN])); } else { /* in the configured dead zone, output zero */ scaled = 0; } /* invert channel if requested */ if (conf[PX4IO_P_RC_CONFIG_OPTIONS] & PX4IO_P_RC_CONFIG_OPTIONS_REVERSE) scaled = -scaled; /* and update the scaled/mapped version */ unsigned mapped = conf[PX4IO_P_RC_CONFIG_ASSIGNMENT]; ASSERT(mapped < PX4IO_CONTROL_CHANNELS); /* invert channel if pitch - pulling the lever down means pitching up by convention */ if (mapped == 1) /* roll, pitch, yaw, throttle, override is the standard order */ scaled = -scaled; r_rc_values[mapped] = SIGNED_TO_REG(scaled); assigned_channels |= (1 << mapped); } } /* set un-assigned controls to zero */ for (unsigned i = 0; i < PX4IO_CONTROL_CHANNELS; i++) { if (!(assigned_channels & (1 << i))) r_rc_values[i] = 0; } /* * If we got an update with zero channels, treat it as * a loss of input. * * This might happen if a protocol-based receiver returns an update * that contains no channels that we have mapped. */ if (assigned_channels == 0 || rssi == 0) { rc_input_lost = true; } else { /* set RC OK flag */ r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_OK; } /* * Export the valid channel bitmap */ r_rc_valid = assigned_channels; } /* * If we haven't seen any new control data in 200ms, assume we * have lost input. */ if (hrt_elapsed_time(&system_state.rc_channels_timestamp) > 200000) { rc_input_lost = true; /* clear the input-kind flags here */ r_status_flags &= ~( PX4IO_P_STATUS_FLAGS_RC_PPM | PX4IO_P_STATUS_FLAGS_RC_DSM | PX4IO_P_STATUS_FLAGS_RC_SBUS); } /* * Handle losing RC input */ if (rc_input_lost) { /* Clear the RC input status flag, clear manual override flag */ r_status_flags &= ~( PX4IO_P_STATUS_FLAGS_OVERRIDE | PX4IO_P_STATUS_FLAGS_RC_OK); /* Set the RC_LOST alarm */ r_status_alarms |= PX4IO_P_STATUS_ALARMS_RC_LOST; /* Mark the arrays as empty */ r_raw_rc_count = 0; r_rc_valid = 0; } /* * Check for manual override. * * The PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK flag must be set, and we * must have R/C input. * Override is enabled if either the hardcoded channel / value combination * is selected, or the AP has requested it. */ if ((r_setup_arming & PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK) && (r_status_flags & PX4IO_P_STATUS_FLAGS_RC_OK)) { bool override = false; /* * Check mapped channel 5 (can be any remote channel, * depends on RC_MAP_OVER parameter); * If the value is 'high' then the pilot has * requested override. * */ if ((r_status_flags & PX4IO_P_STATUS_FLAGS_RC_OK) && (REG_TO_SIGNED(r_rc_values[4]) > RC_CHANNEL_HIGH_THRESH)) override = true; if (override) { r_status_flags |= PX4IO_P_STATUS_FLAGS_OVERRIDE; /* mix new RC input control values to servos */ if (dsm_updated || sbus_updated || ppm_updated) mixer_tick(); } else {
int UBX::receive(unsigned timeout) { /* poll descriptor */ pollfd fds[1]; fds[0].fd = _fd; fds[0].events = POLLIN; uint8_t buf[128]; /* timeout additional to poll */ uint64_t time_started = hrt_absolute_time(); ssize_t count = 0; bool handled = false; while (true) { /* poll for new data, wait for only UBX_PACKET_TIMEOUT (2ms) if something already received */ int ret = poll(fds, sizeof(fds) / sizeof(fds[0]), handled ? UBX_PACKET_TIMEOUT : timeout); if (ret < 0) { /* something went wrong when polling */ warnx("ubx: poll error"); return -1; } else if (ret == 0) { /* return success after short delay after receiving a packet or timeout after long delay */ if (handled) { return 1; } else { return -1; } } else if (ret > 0) { /* if we have new data from GPS, go handle it */ if (fds[0].revents & POLLIN) { /* * We are here because poll says there is some data, so this * won't block even on a blocking device. But don't read immediately * by 1-2 bytes, wait for some more data to save expensive read() calls. * If more bytes are available, we'll go back to poll() again. */ usleep(UBX_WAIT_BEFORE_READ * 1000); count = read(_fd, buf, sizeof(buf)); /* pass received bytes to the packet decoder */ for (int i = 0; i < count; i++) { if (parse_char(buf[i]) > 0) { if (handle_message() > 0) handled = true; } } } } /* abort after timeout if no useful packets received */ if (time_started + timeout * 1000 < hrt_absolute_time()) { warnx("ubx: timeout - no useful messages"); return -1; } } }
int UBX::handle_message() { int ret = 0; if (_configured) { /* handle only info messages when configured */ switch (_message_class) { case UBX_CLASS_NAV: switch (_message_id) { case UBX_MESSAGE_NAV_POSLLH: { // printf("GOT NAV_POSLLH\n"); gps_bin_nav_posllh_packet_t *packet = (gps_bin_nav_posllh_packet_t *) _rx_buffer; _gps_position->lat = packet->lat; _gps_position->lon = packet->lon; _gps_position->alt = packet->height_msl; _gps_position->eph_m = (float)packet->hAcc * 1e-3f; // from mm to m _gps_position->epv_m = (float)packet->vAcc * 1e-3f; // from mm to m _gps_position->timestamp_position = hrt_absolute_time(); _rate_count_lat_lon++; ret = 1; break; } case UBX_MESSAGE_NAV_SOL: { // printf("GOT NAV_SOL\n"); gps_bin_nav_sol_packet_t *packet = (gps_bin_nav_sol_packet_t *) _rx_buffer; _gps_position->fix_type = packet->gpsFix; _gps_position->s_variance_m_s = packet->sAcc; _gps_position->p_variance_m = packet->pAcc; _gps_position->timestamp_variance = hrt_absolute_time(); ret = 1; break; } case UBX_MESSAGE_NAV_TIMEUTC: { // printf("GOT NAV_TIMEUTC\n"); gps_bin_nav_timeutc_packet_t *packet = (gps_bin_nav_timeutc_packet_t *) _rx_buffer; /* convert to unix timestamp */ struct tm timeinfo; timeinfo.tm_year = packet->year - 1900; timeinfo.tm_mon = packet->month - 1; timeinfo.tm_mday = packet->day; timeinfo.tm_hour = packet->hour; timeinfo.tm_min = packet->min; timeinfo.tm_sec = packet->sec; time_t epoch = mktime(&timeinfo); #ifndef CONFIG_RTC //Since we lack a hardware RTC, set the system time clock based on GPS UTC //TODO generalize this by moving into gps.cpp? timespec ts; ts.tv_sec = epoch; ts.tv_nsec = packet->time_nanoseconds; clock_settime(CLOCK_REALTIME, &ts); #endif _gps_position->time_gps_usec = (uint64_t)epoch * 1000000; //TODO: test this _gps_position->time_gps_usec += (uint64_t)(packet->time_nanoseconds * 1e-3f); _gps_position->timestamp_time = hrt_absolute_time(); ret = 1; break; } case UBX_MESSAGE_NAV_SVINFO: { //printf("GOT NAV_SVINFO\n"); const int length_part1 = 8; gps_bin_nav_svinfo_part1_packet_t *packet_part1 = (gps_bin_nav_svinfo_part1_packet_t *) _rx_buffer; const int length_part2 = 12; gps_bin_nav_svinfo_part2_packet_t *packet_part2; uint8_t satellites_used = 0; int i; //printf("Number of Channels: %d\n", packet_part1->numCh); for (i = 0; i < packet_part1->numCh; i++) { /* set pointer to sattelite_i information */ packet_part2 = (gps_bin_nav_svinfo_part2_packet_t *) & (_rx_buffer[length_part1 + i * length_part2]); /* write satellite information to global storage */ uint8_t sv_used = packet_part2->flags & 0x01; if (sv_used) { /* count SVs used for NAV */ satellites_used++; } /* record info for all channels, whether or not the SV is used for NAV */ _gps_position->satellite_used[i] = sv_used; _gps_position->satellite_snr[i] = packet_part2->cno; _gps_position->satellite_elevation[i] = (uint8_t)(packet_part2->elev); _gps_position->satellite_azimuth[i] = (uint8_t)((float)packet_part2->azim * 255.0f / 360.0f); _gps_position->satellite_prn[i] = packet_part2->svid; //printf("SAT %d: %d %d %d %d\n", i, (int)sv_used, (int)packet_part2->cno, (int)(uint8_t)(packet_part2->elev), (int)packet_part2->svid); } for (i = packet_part1->numCh; i < 20; i++) { /* unused channels have to be set to zero for e.g. MAVLink */ _gps_position->satellite_prn[i] = 0; _gps_position->satellite_used[i] = 0; _gps_position->satellite_snr[i] = 0; _gps_position->satellite_elevation[i] = 0; _gps_position->satellite_azimuth[i] = 0; } _gps_position->satellites_visible = satellites_used; // visible ~= used but we are interested in the used ones if (packet_part1->numCh > 0) { _gps_position->satellite_info_available = true; } else { _gps_position->satellite_info_available = false; } _gps_position->timestamp_satellites = hrt_absolute_time(); ret = 1; break; } case UBX_MESSAGE_NAV_VELNED: { // printf("GOT NAV_VELNED\n"); gps_bin_nav_velned_packet_t *packet = (gps_bin_nav_velned_packet_t *) _rx_buffer; _gps_position->vel_m_s = (float)packet->speed * 1e-2f; _gps_position->vel_n_m_s = (float)packet->velN * 1e-2f; /* NED NORTH velocity */ _gps_position->vel_e_m_s = (float)packet->velE * 1e-2f; /* NED EAST velocity */ _gps_position->vel_d_m_s = (float)packet->velD * 1e-2f; /* NED DOWN velocity */ _gps_position->cog_rad = (float)packet->heading * M_DEG_TO_RAD_F * 1e-5f; _gps_position->c_variance_rad = (float)packet->cAcc * M_DEG_TO_RAD_F * 1e-5f; _gps_position->vel_ned_valid = true; _gps_position->timestamp_velocity = hrt_absolute_time(); _rate_count_vel++; ret = 1; break; } default: break; } break; case UBX_CLASS_ACK: { /* ignore ACK when already configured */ ret = 1; break; } default: break; } if (ret == 0) { /* message not handled */ warnx("ubx: unknown message received: 0x%02x-0x%02x", (unsigned)_message_class, (unsigned)_message_id); hrt_abstime t = hrt_absolute_time(); if (t > _disable_cmd_last + DISABLE_MSG_INTERVAL) { /* don't attempt for every message to disable, some might not be disabled */ _disable_cmd_last = t; warnx("ubx: disabling message 0x%02x-0x%02x", (unsigned)_message_class, (unsigned)_message_id); configure_message_rate(_message_class, _message_id, 0); } } } else { /* handle only ACK while configuring */ if (_message_class == UBX_CLASS_ACK) { switch (_message_id) { case UBX_MESSAGE_ACK_ACK: { // printf("GOT ACK_ACK\n"); gps_bin_ack_ack_packet_t *packet = (gps_bin_ack_ack_packet_t *) _rx_buffer; if (_waiting_for_ack) { if (packet->clsID == _message_class_needed && packet->msgID == _message_id_needed) { _waiting_for_ack = false; ret = 1; } } break; } case UBX_MESSAGE_ACK_NAK: { // printf("GOT ACK_NAK\n"); warnx("ubx: not acknowledged"); /* configuration obviously not successful */ _waiting_for_ack = false; ret = -1; break; } default: break; } } } decode_init(); return ret; }
/* * Handle the PPM decoder state machine. */ static void hrt_ppm_decode(uint32_t status) { uint16_t count = rCCR_PPM; uint16_t width; uint16_t interval; unsigned i; /* if we missed an edge, we have to give up */ if (status & SR_OVF_PPM) goto error; /* how long since the last edge? - this handles counter wrapping implicitely. */ width = count - ppm.last_edge; ppm_edge_history[ppm_edge_next++] = width; if (ppm_edge_next >= 32) ppm_edge_next = 0; /* * if this looks like a start pulse, then push the last set of values * and reset the state machine */ if (width >= PPM_MIN_START) { /* * If the number of channels changes unexpectedly, we don't want * to just immediately jump on the new count as it may be a result * of noise or dropped edges. Instead, take a few frames to settle. */ if (ppm.next_channel != ppm_decoded_channels) { static unsigned new_channel_count; static unsigned new_channel_holdoff; if (new_channel_count != ppm.next_channel) { /* start the lock counter for the new channel count */ new_channel_count = ppm.next_channel; new_channel_holdoff = PPM_CHANNEL_LOCK; } else if (new_channel_holdoff > 0) { /* this frame matched the last one, decrement the lock counter */ new_channel_holdoff--; } else { /* we have seen PPM_CHANNEL_LOCK frames with the new count, accept it */ ppm_decoded_channels = new_channel_count; new_channel_count = 0; } } else { /* frame channel count matches expected, let's use it */ if (ppm.next_channel > PPM_MIN_CHANNELS) { for (i = 0; i < ppm.next_channel; i++) ppm_buffer[i] = ppm_temp_buffer[i]; ppm_last_valid_decode = hrt_absolute_time(); } } /* reset for the next frame */ ppm.next_channel = 0; /* next edge is the reference for the first channel */ ppm.phase = ARM; ppm.last_edge = count; return; } switch (ppm.phase) { case UNSYNCH: /* we are waiting for a start pulse - nothing useful to do here */ break; case ARM: /* we expect a pulse giving us the first mark */ if (width < PPM_MIN_PULSE_WIDTH || width > PPM_MAX_PULSE_WIDTH) goto error; /* pulse was too short or too long */ /* record the mark timing, expect an inactive edge */ ppm.last_mark = ppm.last_edge; /* frame length is everything including the start gap */ ppm_frame_length = (uint16_t)(ppm.last_edge - ppm.frame_start); ppm.frame_start = ppm.last_edge; ppm.phase = ACTIVE; break; case INACTIVE: /* we expect a short pulse */ if (width < PPM_MIN_PULSE_WIDTH || width > PPM_MAX_PULSE_WIDTH) goto error; /* pulse was too short or too long */ /* this edge is not interesting, but now we are ready for the next mark */ ppm.phase = ACTIVE; break; case ACTIVE: /* determine the interval from the last mark */ interval = count - ppm.last_mark; ppm.last_mark = count; ppm_pulse_history[ppm_pulse_next++] = interval; if (ppm_pulse_next >= 32) ppm_pulse_next = 0; /* if the mark-mark timing is out of bounds, abandon the frame */ if ((interval < PPM_MIN_CHANNEL_VALUE) || (interval > PPM_MAX_CHANNEL_VALUE)) goto error; /* if we have room to store the value, do so */ if (ppm.next_channel < PPM_MAX_CHANNELS) ppm_temp_buffer[ppm.next_channel++] = interval; ppm.phase = INACTIVE; break; } ppm.last_edge = count; return; /* the state machine is corrupted; reset it */ error: /* we don't like the state of the decoder, reset it and try again */ ppm.phase = UNSYNCH; ppm_decoded_channels = 0; }
void hrt_call_delay(struct hrt_call *entry, hrt_abstime delay) { entry->deadline = hrt_absolute_time() + delay; }
bool MissionBlock::is_mission_item_reached() { /* handle non-navigation or indefinite waypoints */ switch (_mission_item.nav_cmd) { case NAV_CMD_DO_SET_SERVO: return true; case NAV_CMD_LAND: /* fall through */ case NAV_CMD_VTOL_LAND: return _navigator->get_land_detected()->landed; case NAV_CMD_IDLE: /* fall through */ case NAV_CMD_LOITER_UNLIMITED: return false; case NAV_CMD_DO_DIGICAM_CONTROL: case NAV_CMD_IMAGE_START_CAPTURE: case NAV_CMD_IMAGE_STOP_CAPTURE: case NAV_CMD_VIDEO_START_CAPTURE: case NAV_CMD_VIDEO_STOP_CAPTURE: case NAV_CMD_DO_MOUNT_CONFIGURE: case NAV_CMD_DO_MOUNT_CONTROL: case NAV_CMD_DO_SET_ROI: case NAV_CMD_ROI: case NAV_CMD_DO_SET_CAM_TRIGG_DIST: return true; case NAV_CMD_DO_VTOL_TRANSITION: /* * We wait half a second to give the transition command time to propagate. * Then monitor the transition status for completion. */ if (hrt_absolute_time() - _action_start > 500000 && !_navigator->get_vstatus()->in_transition_mode) { _action_start = 0; return true; } else { return false; } case NAV_CMD_DO_CHANGE_SPEED: // XXX not differentiating ground and airspeed yet if (_mission_item.params[1] > 0.0f) { _navigator->set_cruising_speed(_mission_item.params[1]); } else { _navigator->set_cruising_speed(); /* if no speed target was given try to set throttle */ if (_mission_item.params[2] > 0.0f) { _navigator->set_cruising_throttle(_mission_item.params[2] / 100); } else { _navigator->set_cruising_throttle(); } } return true; default: /* do nothing, this is a 3D waypoint */ break; } hrt_abstime now = hrt_absolute_time(); if ((_navigator->get_land_detected()->landed == false) && !_waypoint_position_reached) { float dist = -1.0f; float dist_xy = -1.0f; float dist_z = -1.0f; float altitude_amsl = _mission_item.altitude_is_relative ? _mission_item.altitude + _navigator->get_home_position()->alt : _mission_item.altitude; dist = get_distance_to_point_global_wgs84(_mission_item.lat, _mission_item.lon, altitude_amsl, _navigator->get_global_position()->lat, _navigator->get_global_position()->lon, _navigator->get_global_position()->alt, &dist_xy, &dist_z); if ((_mission_item.nav_cmd == NAV_CMD_TAKEOFF || _mission_item.nav_cmd == NAV_CMD_VTOL_TAKEOFF) && _navigator->get_vstatus()->is_rotary_wing) { /* We want to avoid the edge case where the acceptance radius is bigger or equal than * the altitude of the takeoff waypoint above home. Otherwise, we do not really follow * take-off procedures like leaving the landing gear down. */ float takeoff_alt = _mission_item.altitude_is_relative ? _mission_item.altitude : (_mission_item.altitude - _navigator->get_home_position()->alt); float altitude_acceptance_radius = _navigator->get_altitude_acceptance_radius(); /* It should be safe to just use half of the takoeff_alt as an acceptance radius. */ if (takeoff_alt > 0 && takeoff_alt < altitude_acceptance_radius) { altitude_acceptance_radius = takeoff_alt / 2.0f; } /* require only altitude for takeoff for multicopter */ if (_navigator->get_global_position()->alt > altitude_amsl - altitude_acceptance_radius) { _waypoint_position_reached = true; } } else if (_mission_item.nav_cmd == NAV_CMD_TAKEOFF) { /* for takeoff mission items use the parameter for the takeoff acceptance radius */ if (dist >= 0.0f && dist <= _navigator->get_acceptance_radius() && dist_z <= _navigator->get_altitude_acceptance_radius()) { _waypoint_position_reached = true; } } else if (!_navigator->get_vstatus()->is_rotary_wing && (_mission_item.nav_cmd == NAV_CMD_LOITER_UNLIMITED || _mission_item.nav_cmd == NAV_CMD_LOITER_TIME_LIMIT)) { /* Loiter mission item on a non rotary wing: the aircraft is going to circle the * coordinates with a radius equal to the loiter_radius field. It is not flying * through the waypoint center. * Therefore the item is marked as reached once the system reaches the loiter * radius (+ some margin). Time inside and turn count is handled elsewhere. */ if (dist >= 0.0f && dist <= _navigator->get_acceptance_radius(fabsf(_mission_item.loiter_radius) * 1.2f) && dist_z <= _navigator->get_altitude_acceptance_radius()) { _waypoint_position_reached = true; } else { _time_first_inside_orbit = 0; } } else if (!_navigator->get_vstatus()->is_rotary_wing && (_mission_item.nav_cmd == NAV_CMD_LOITER_TO_ALT)) { // NAV_CMD_LOITER_TO_ALT only uses mission item altitude once it's in the loiter // first check if the altitude setpoint is the mission setpoint struct position_setpoint_s *curr_sp = &_navigator->get_position_setpoint_triplet()->current; if (fabsf(curr_sp->alt - altitude_amsl) >= FLT_EPSILON) { // check if the initial loiter has been accepted dist = -1.0f; dist_xy = -1.0f; dist_z = -1.0f; dist = get_distance_to_point_global_wgs84(_mission_item.lat, _mission_item.lon, curr_sp->alt, _navigator->get_global_position()->lat, _navigator->get_global_position()->lon, _navigator->get_global_position()->alt, &dist_xy, &dist_z); if (dist >= 0.0f && dist <= _navigator->get_acceptance_radius(fabsf(_mission_item.loiter_radius) * 1.2f) && dist_z <= _navigator->get_altitude_acceptance_radius()) { // now set the loiter to the final altitude in the NAV_CMD_LOITER_TO_ALT mission item curr_sp->alt = altitude_amsl; _navigator->set_position_setpoint_triplet_updated(); } } else { if (dist >= 0.0f && dist <= _navigator->get_acceptance_radius(fabsf(_mission_item.loiter_radius) * 1.2f) && dist_z <= _navigator->get_altitude_acceptance_radius()) { _waypoint_position_reached = true; // set required yaw from bearing to the next mission item if (_mission_item.force_heading) { struct position_setpoint_s next_sp = _navigator->get_position_setpoint_triplet()->next; if (next_sp.valid) { _mission_item.yaw = get_bearing_to_next_waypoint(_navigator->get_global_position()->lat, _navigator->get_global_position()->lon, next_sp.lat, next_sp.lon); _waypoint_yaw_reached = false; } else { _waypoint_yaw_reached = true; } } } } } else { /* for normal mission items used their acceptance radius */ float mission_acceptance_radius = _navigator->get_acceptance_radius(_mission_item.acceptance_radius); /* if set to zero use the default instead */ if (mission_acceptance_radius < NAV_EPSILON_POSITION) { mission_acceptance_radius = _navigator->get_acceptance_radius(); } if (dist >= 0.0f && dist <= mission_acceptance_radius && dist_z <= _navigator->get_altitude_acceptance_radius()) { _waypoint_position_reached = true; } } if (_waypoint_position_reached) { // reached just now _time_wp_reached = now; } } /* Check if the waypoint and the requested yaw setpoint. */ if (_waypoint_position_reached && !_waypoint_yaw_reached) { if ((_navigator->get_vstatus()->is_rotary_wing || (_mission_item.nav_cmd == NAV_CMD_LOITER_TO_ALT && _mission_item.force_heading)) && PX4_ISFINITE(_mission_item.yaw)) { /* check yaw if defined only for rotary wing except takeoff */ float yaw_err = _wrap_pi(_mission_item.yaw - _navigator->get_global_position()->yaw); /* accept yaw if reached or if timeout is set in which case we ignore not forced headings */ if (fabsf(yaw_err) < math::radians(_param_yaw_err.get()) || (_param_yaw_timeout.get() >= FLT_EPSILON && !_mission_item.force_heading)) { _waypoint_yaw_reached = true; } /* if heading needs to be reached, the timeout is enabled and we don't make it, abort mission */ if (!_waypoint_yaw_reached && _mission_item.force_heading && (_param_yaw_timeout.get() >= FLT_EPSILON) && (now - _time_wp_reached >= (hrt_abstime)_param_yaw_timeout.get() * 1e6f)) { _navigator->set_mission_failure("unable to reach heading within timeout"); } } else { _waypoint_yaw_reached = true; } } /* Once the waypoint and yaw setpoint have been reached we can start the loiter time countdown */ if (_waypoint_position_reached && _waypoint_yaw_reached) { if (_time_first_inside_orbit == 0) { _time_first_inside_orbit = now; } /* check if the MAV was long enough inside the waypoint orbit */ if ((Navigator::get_time_inside(_mission_item) < FLT_EPSILON) || (now - _time_first_inside_orbit >= (hrt_abstime)(Navigator::get_time_inside(_mission_item) * 1e6f))) { // exit xtrack location if (_mission_item.loiter_exit_xtrack && (_mission_item.nav_cmd == NAV_CMD_LOITER_TIME_LIMIT || _mission_item.nav_cmd == NAV_CMD_LOITER_TO_ALT)) { // reset lat/lon of loiter waypoint so vehicle exits on a tangent struct position_setpoint_s *curr_sp = &_navigator->get_position_setpoint_triplet()->current; curr_sp->lat = _navigator->get_global_position()->lat; curr_sp->lon = _navigator->get_global_position()->lon; } return true; } } // all acceptance criteria must be met in the same iteration _waypoint_position_reached = false; _waypoint_yaw_reached = false; return false; }
int fixedwing_control_main(int argc, char *argv[]) { /* default values for arguments */ char *fixedwing_uart_name = "/dev/ttyS1"; char *commandline_usage = "\tusage: %s -d fixedwing-devicename\n"; /* read arguments */ bool verbose = false; for (int i = 1; i < argc; i++) { if (strcmp(argv[i], "-d") == 0 || strcmp(argv[i], "--device") == 0) { if (argc > i + 1) { fixedwing_uart_name = argv[i + 1]; } else { printf(commandline_usage, argv[0]); return 0; } } if (strcmp(argv[i], "-v") == 0 || strcmp(argv[i], "--verbose") == 0) { verbose = true; } } /* welcome user */ printf("[fixedwing control] started\n"); /* Set up to publish fixed wing control messages */ struct fixedwing_control_s control; int fixedwing_control_pub = orb_advertise(ORB_ID(fixedwing_control), &control); /* Subscribe to global position, attitude and rc */ struct vehicle_global_position_s global_pos; int global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position)); struct vehicle_attitude_s att; int attitude_sub = orb_subscribe(ORB_ID(vehicle_attitude)); struct rc_channels_s rc; int rc_sub = orb_subscribe(ORB_ID(rc_channels)); struct vehicle_global_position_setpoint_s global_setpoint; int global_setpoint_sub = orb_subscribe(ORB_ID(vehicle_global_position_setpoint)); /* Mainloop setup */ unsigned int loopcounter = 0; unsigned int failcounter = 0; /* Control constants */ control_outputs.mode = HIL_MODE; control_outputs.nav_mode = 0; /* Servo setup */ int fd; servo_position_t data[PWM_OUTPUT_MAX_CHANNELS]; fd = open("/dev/pwm_servo", O_RDWR); if (fd < 0) { printf("[fixedwing control] Failed opening /dev/pwm_servo\n"); } ioctl(fd, PWM_SERVO_ARM, 0); int16_t buffer_rc[3]; int16_t buffer_servo[3]; mixer_data_t mixer_buffer; mixer_buffer.input = buffer_rc; mixer_buffer.output = buffer_servo; mixer_conf_t mixers[3]; mixers[0].source = PITCH; mixers[0].nr_actuators = 2; mixers[0].dest[0] = AIL_1; mixers[0].dest[1] = AIL_2; mixers[0].dual_rate[0] = 1; mixers[0].dual_rate[1] = 1; mixers[1].source = ROLL; mixers[1].nr_actuators = 2; mixers[1].dest[0] = AIL_1; mixers[1].dest[1] = AIL_2; mixers[1].dual_rate[0] = 1; mixers[1].dual_rate[1] = -1; mixers[2].source = THROTTLE; mixers[2].nr_actuators = 1; mixers[2].dest[0] = MOT; mixers[2].dual_rate[0] = 1; /* * Main control, navigation and servo routine */ while(1) { /* * DATA Handling * Fetch current flight data */ /* get position, attitude and rc inputs */ // XXX add error checking orb_copy(ORB_ID(vehicle_global_position), global_pos_sub, &global_pos); orb_copy(ORB_ID(vehicle_global_position_setpoint), global_setpoint_sub, &global_setpoint); orb_copy(ORB_ID(vehicle_attitude), attitude_sub, &att); orb_copy(ORB_ID(rc_channels), rc_sub, &rc); /* scaling factors are defined by the data from the APM Planner * TODO: ifdef for other parameters (HIL/Real world switch) */ /* position values*/ plane_data.lat = global_pos.lat / 10000000.0; plane_data.lon = global_pos.lon / 10000000.0; plane_data.alt = global_pos.alt / 1000.0f; plane_data.vx = global_pos.vx / 100.0f; plane_data.vy = global_pos.vy / 100.0f; plane_data.vz = global_pos.vz / 100.0f; /* attitude values*/ plane_data.roll = att.roll; plane_data.pitch = att.pitch; plane_data.yaw = att.yaw; plane_data.rollspeed = att.rollspeed; plane_data.pitchspeed = att.pitchspeed; plane_data.yawspeed = att.yawspeed; /* parameter values */ get_parameters(&plane_data); /* Attitude control part */ if (verbose && loopcounter % 20 == 0) { /******************************** DEBUG OUTPUT ************************************************************/ printf("Parameter: %i,%i,%i,%i,%i,%i,%i,%i,%i,%i,%i,%i,%i,%i,%i \n", (int)plane_data.Kp_att, (int)plane_data.Ki_att, (int)plane_data.Kd_att, (int)plane_data.intmax_att, (int)plane_data.Kp_pos, (int)plane_data.Ki_pos, (int)plane_data.Kd_pos, (int)plane_data.intmax_pos, (int)plane_data.airspeed, (int)plane_data.wp_x, (int)plane_data.wp_y, (int)plane_data.wp_z, (int)global_data_parameter_storage->pm.param_values[PARAM_WPLON], (int)global_data_parameter_storage->pm.param_values[PARAM_WPLAT], (int)global_data_parameter_storage->pm.param_values[PARAM_WPALT]); printf("PITCH SETPOINT: %i\n", (int)(100.0f*plane_data.pitch_setpoint)); printf("ROLL SETPOINT: %i\n", (int)(100.0f*plane_data.roll_setpoint)); printf("THROTTLE SETPOINT: %i\n", (int)(100.0f*calc_throttle_setpoint())); // printf("\n\nVx: %i\t Vy: %i\t Current speed:%i\n\n", (int)plane_data.vx, (int)plane_data.vy, (int)(calc_gnd_speed())); // printf("Current Altitude: %i\n\n", (int)plane_data.alt); printf("\nAttitude values: \n R:%i \n P: %i \n Y: %i \n\n RS: %i \n PS: %i \n YS: %i \n ", (int)(180.0f * plane_data.roll/F_M_PI), (int)(180.0f * plane_data.pitch/F_M_PI), (int)(180.0f * plane_data.yaw/F_M_PI), (int)(180.0f * plane_data.rollspeed/F_M_PI), (int)(180.0f * plane_data.pitchspeed/F_M_PI), (int)(180.0f * plane_data.yawspeed)/F_M_PI); // printf("\nBody Rates: \n P: %i \n Q: %i \n R: %i \n", // (int)(10000 * plane_data.p), (int)(10000 * plane_data.q), (int)(10000 * plane_data.r)); printf("\nCalculated outputs: \n R: %i\n P: %i\n Y: %i\n T: %i \n", (int)(10000.0f * control_outputs.roll_ailerons), (int)(10000.0f * control_outputs.pitch_elevator), (int)(10000.0f * control_outputs.yaw_rudder), (int)(10000.0f * control_outputs.throttle)); /************************************************************************************************************/ } /* * Computation section * * The function calls to compute the required control values happen * in this section. */ /* Set plane mode */ set_plane_mode(); /* Calculate the P,Q,R body rates of the aircraft */ //calc_body_angular_rates(plane_data.roll, plane_data.pitch, plane_data.yaw, // plane_data.rollspeed, plane_data.pitchspeed, plane_data.yawspeed); /* Calculate the body frame angles of the aircraft */ //calc_bodyframe_angles(plane_data.roll,plane_data.pitch,plane_data.yaw); /* Calculate the output values */ control_outputs.roll_ailerons = calc_roll_ail(); control_outputs.pitch_elevator = calc_pitch_elev(); //control_outputs.yaw_rudder = calc_yaw_rudder(); control_outputs.throttle = calc_throttle(); if (rc.chan[rc.function[OVERRIDE]].scale < MANUAL) { // if we're flying in automated mode /* * TAKEOFF hack for HIL */ if (plane_data.mode == TAKEOFF) { control.attitude_control_output[ROLL] = 0; control.attitude_control_output[PITCH] = 5000; control.attitude_control_output[THROTTLE] = 10000; //global_data_fixedwing_control->attitude_control_output[YAW] = (int16_t)(control_outputs.yaw_rudder); } if (plane_data.mode == CRUISE) { control.attitude_control_output[ROLL] = control_outputs.roll_ailerons; control.attitude_control_output[PITCH] = control_outputs.pitch_elevator; control.attitude_control_output[THROTTLE] = control_outputs.throttle; //control->attitude_control_output[YAW] = (int16_t)(control_outputs.yaw_rudder); } control.counter++; control.timestamp = hrt_absolute_time(); } /* Navigation part */ // Get GPS Waypoint // if(global_data_wait(&global_data_position_setpoint->access_conf) == 0) // { // plane_data.wp_x = global_data_position_setpoint->x; // plane_data.wp_y = global_data_position_setpoint->y; // plane_data.wp_z = global_data_position_setpoint->z; // } // global_data_unlock(&global_data_position_setpoint->access_conf); if (rc.chan[rc.function[OVERRIDE]].scale < MANUAL) { // AUTO mode // AUTO/HYBRID switch if (rc.chan[rc.function[OVERRIDE]].scale < AUTO) { plane_data.roll_setpoint = calc_roll_setpoint(); plane_data.pitch_setpoint = calc_pitch_setpoint(); plane_data.throttle_setpoint = calc_throttle_setpoint(); } else { plane_data.roll_setpoint = rc.chan[rc.function[ROLL]].scale / 200; plane_data.pitch_setpoint = rc.chan[rc.function[PITCH]].scale / 200; plane_data.throttle_setpoint = rc.chan[rc.function[THROTTLE]].scale / 200; } //control_outputs.yaw_rudder = calc_yaw_rudder(plane_data.hdg); } else { control.attitude_control_output[ROLL] = rc.chan[rc.function[ROLL]].scale/10000; control.attitude_control_output[PITCH] = rc.chan[rc.function[PITCH]].scale/10000; control.attitude_control_output[THROTTLE] = rc.chan[rc.function[THROTTLE]].scale/10000; // since we don't have a yaw rudder //control->attitude_control_output[3] = global_data_rc_channels->chan[YAW].scale; control.counter++; control.timestamp = hrt_absolute_time(); } /* publish the control data */ orb_publish(ORB_ID(fixedwing_control), fixedwing_control_pub, &control); /* Servo part */ buffer_rc[ROLL] = (int16_t)(10000*control.attitude_control_output[ROLL]); buffer_rc[PITCH] = (int16_t)(10000*control.attitude_control_output[PITCH]); buffer_rc[THROTTLE] = (int16_t)(10000*control.attitude_control_output[THROTTLE]); //mix_and_link(mixers, 3, 2, &mixer_buffer); // Scaling and saturation of servo outputs happens here data[AIL_1] = buffer_servo[AIL_1] / global_data_parameter_storage->pm.param_values[PARAM_SERVO_SCALE] + global_data_parameter_storage->pm.param_values[PARAM_SERVO1_TRIM]; if (data[AIL_1] > SERVO_MAX) data[AIL_1] = SERVO_MAX; if (data[AIL_1] < SERVO_MIN) data[AIL_1] = SERVO_MIN; data[AIL_2] = buffer_servo[AIL_2] / global_data_parameter_storage->pm.param_values[PARAM_SERVO_SCALE] + global_data_parameter_storage->pm.param_values[PARAM_SERVO2_TRIM]; if (data[AIL_2] > SERVO_MAX) data[AIL_2] = SERVO_MAX; if (data[AIL_2] < SERVO_MIN) data[AIL_2] = SERVO_MIN; data[MOT] = buffer_servo[MOT] / global_data_parameter_storage->pm.param_values[PARAM_SERVO_SCALE] + global_data_parameter_storage->pm.param_values[PARAM_SERVO3_TRIM]; if (data[MOT] > SERVO_MAX) data[MOT] = SERVO_MAX; if (data[MOT] < SERVO_MIN) data[MOT] = SERVO_MIN; int result = write(fd, &data, sizeof(data)); if (result != sizeof(data)) { if (failcounter < 10 || failcounter % 20 == 0) { printf("[fixedwing_control] failed writing servo outputs\n"); } failcounter++; } loopcounter++; /* 20Hz loop*/ usleep(50000); } return 0; }
void comms_check(void) { /* * Check for serial data */ int ret = poll(pollfds, pollcount, 0); if (ret > 0) { /* * Pull bytes from FMU and feed them to the HX engine. * Limit the number of bytes we actually process on any one iteration. */ if (pollfds[0].revents & POLLIN) { char buf[32]; ssize_t count = read(fmu_fd, buf, sizeof(buf)); for (int i = 0; i < count; i++) hx_stream_rx(stream, buf[i]); } /* * Pull bytes from the serial RX port and feed them to the decoder * if we care about serial RX data. */ if ((pollcount > 1) && (pollfds[1].revents & POLLIN)) { switch (system_state.serial_rx_mode) { case RX_MODE_DSM_10BIT: case RX_MODE_DSM_11BIT: dsm_input(rx_fd); break; case RX_MODE_FUTABA_SBUS: sbus_input(rx_fd); break; default: break; } } } /* * Decide if it's time to send an update to the FMU. */ static hrt_abstime last_report_time; hrt_abstime now, delta; /* should we send a report to the FMU? */ now = hrt_absolute_time(); delta = now - last_report_time; if ((delta > FMU_MIN_REPORT_INTERVAL) && (system_state.fmu_report_due || (delta > FMU_MAX_REPORT_INTERVAL))) { system_state.fmu_report_due = false; last_report_time = now; /* populate the report */ for (int i = 0; i < system_state.rc_channels; i++) report.rc_channel[i] = system_state.rc_channel_data[i]; report.channel_count = system_state.rc_channels; report.armed = system_state.armed; /* and send it */ hx_stream_send(stream, &report, sizeof(report)); } }
struct sensor_combined_s sensor; /* exponential moving average of accel */ float accel_ema[3] = { 0.0f, 0.0f, 0.0f }; /* max-hold dispersion of accel */ float accel_disp[3] = { 0.0f, 0.0f, 0.0f }; /* EMA time constant in seconds*/ float ema_len = 0.2f; /* set "still" threshold to 0.1 m/s^2 */ float still_thr2 = pow(0.1f, 2); /* set accel error threshold to 5m/s^2 */ float accel_err_thr = 5.0f; /* still time required in us */ int64_t still_time = 2000000; struct pollfd fds[1] = { { .fd = sub_sensor_combined, .events = POLLIN } }; hrt_abstime t_start = hrt_absolute_time(); /* set timeout to 30s */ hrt_abstime timeout = 30000000; hrt_abstime t_timeout = t_start + timeout; hrt_abstime t = t_start; hrt_abstime t_prev = t_start; hrt_abstime t_still = 0; while (true) { /* wait blocking for new data */ int poll_ret = poll(fds, 1, 1000); if (poll_ret) { orb_copy(ORB_ID(sensor_combined), sub_sensor_combined, &sensor); t = hrt_absolute_time(); float dt = (t - t_prev) / 1000000.0f; t_prev = t; float w = dt / ema_len;
int registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num_values) { switch (page) { /* handle bulk controls input */ case PX4IO_PAGE_CONTROLS: /* copy channel data */ while ((offset < PX4IO_CONTROL_CHANNELS) && (num_values > 0)) { /* XXX range-check value? */ r_page_controls[offset] = *values; offset++; num_values--; values++; } system_state.fmu_data_received_time = hrt_absolute_time(); r_status_flags |= PX4IO_P_STATUS_FLAGS_FMU_OK; r_status_flags &= ~PX4IO_P_STATUS_FLAGS_RAW_PWM; break; /* handle raw PWM input */ case PX4IO_PAGE_DIRECT_PWM: /* copy channel data */ while ((offset < PX4IO_CONTROL_CHANNELS) && (num_values > 0)) { /* XXX range-check value? */ r_page_servos[offset] = *values; offset++; num_values--; values++; } system_state.fmu_data_received_time = hrt_absolute_time(); r_status_flags |= PX4IO_P_STATUS_FLAGS_FMU_OK | PX4IO_P_STATUS_FLAGS_RAW_PWM; break; /* handle setup for servo failsafe values */ case PX4IO_PAGE_FAILSAFE_PWM: /* copy channel data */ while ((offset < PX4IO_SERVO_COUNT) && (num_values > 0)) { if (*values == 0) { /* ignore 0 */ } else if (*values < PWM_LOWEST_MIN) { r_page_servo_failsafe[offset] = PWM_LOWEST_MIN; } else if (*values > PWM_HIGHEST_MAX) { r_page_servo_failsafe[offset] = PWM_HIGHEST_MAX; } else { r_page_servo_failsafe[offset] = *values; } /* flag the failsafe values as custom */ r_setup_arming |= PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM; offset++; num_values--; values++; } break; case PX4IO_PAGE_CONTROL_MIN_PWM: /* copy channel data */ while ((offset < PX4IO_SERVO_COUNT) && (num_values > 0)) { if (*values == 0) { /* ignore 0 */ } else if (*values > PWM_HIGHEST_MIN) { r_page_servo_control_min[offset] = PWM_HIGHEST_MIN; } else if (*values < PWM_LOWEST_MIN) { r_page_servo_control_min[offset] = PWM_LOWEST_MIN; } else { r_page_servo_control_min[offset] = *values; } offset++; num_values--; values++; } break; case PX4IO_PAGE_CONTROL_MAX_PWM: /* copy channel data */ while ((offset < PX4IO_SERVO_COUNT) && (num_values > 0)) { if (*values == 0) { /* ignore 0 */ } else if (*values > PWM_HIGHEST_MAX) { r_page_servo_control_max[offset] = PWM_HIGHEST_MAX; } else if (*values < PWM_LOWEST_MAX) { r_page_servo_control_max[offset] = PWM_LOWEST_MAX; } else { r_page_servo_control_max[offset] = *values; } offset++; num_values--; values++; } break; case PX4IO_PAGE_DISARMED_PWM: { /* flag for all outputs */ bool all_disarmed_off = true; /* copy channel data */ while ((offset < PX4IO_SERVO_COUNT) && (num_values > 0)) { if (*values == 0) { /* 0 means disabling always PWM */ r_page_servo_disarmed[offset] = 0; } else if (*values < PWM_LOWEST_MIN) { r_page_servo_disarmed[offset] = PWM_LOWEST_MIN; all_disarmed_off = false; } else if (*values > PWM_HIGHEST_MAX) { r_page_servo_disarmed[offset] = PWM_HIGHEST_MAX; all_disarmed_off = false; } else { r_page_servo_disarmed[offset] = *values; all_disarmed_off = false; } offset++; num_values--; values++; } if (all_disarmed_off) { /* disable PWM output if disarmed */ r_setup_arming &= ~(PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE); } else { /* enable PWM output always */ r_setup_arming |= PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE; } } break; /* handle text going to the mixer parser */ case PX4IO_PAGE_MIXERLOAD: mixer_handle_text(values, num_values * sizeof(*values)); break; default: /* avoid offset wrap */ if ((offset + num_values) > 255) num_values = 255 - offset; /* iterate individual registers, set each in turn */ while (num_values--) { if (registers_set_one(page, offset, *values)) return -1; offset++; values++; } break; } return 0; }
void MavlinkMissionManager::handle_mission_request_both(const mavlink_message_t *msg) { /* The mavlink_message_t could also be a mavlink_mission_request_int_t, however the structs * are basically the same, so we can ignore it. */ mavlink_mission_request_t wpr; mavlink_msg_mission_request_decode(msg, &wpr); if (CHECK_SYSID_COMPID_MISSION(wpr)) { if (msg->sysid == _transfer_partner_sysid && msg->compid == _transfer_partner_compid) { if (_state == MAVLINK_WPM_STATE_SENDLIST) { _time_last_recv = hrt_absolute_time(); /* _transfer_seq contains sequence of expected request */ if (wpr.seq == _transfer_seq && _transfer_seq < _transfer_count) { if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST(_INT) seq %u from ID %u", wpr.seq, msg->sysid); } _transfer_seq++; } else if (wpr.seq == _transfer_seq - 1) { if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST(_INT) seq %u from ID %u (again)", wpr.seq, msg->sysid); } } else { if (_transfer_seq > 0 && _transfer_seq < _transfer_count) { if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST(_INT) ERROR: seq %u from ID %u unexpected, must be %i or %i", wpr.seq, msg->sysid, _transfer_seq - 1, _transfer_seq); } } else if (_transfer_seq <= 0) { if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST(_INT) ERROR: seq %u from ID %u unexpected, must be %i", wpr.seq, msg->sysid, _transfer_seq); } } else { if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST(_INT) ERROR: seq %u from ID %u unexpected, must be %i", wpr.seq, msg->sysid, _transfer_seq - 1); } } _state = MAVLINK_WPM_STATE_IDLE; send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR); _mavlink->send_statustext_critical("WPM: REJ. CMD: Req. WP was unexpected"); return; } /* double check bounds in case of items count changed */ if (wpr.seq < _count) { send_mission_item(_transfer_partner_sysid, _transfer_partner_compid, wpr.seq); } else { if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST(_INT) ERROR: seq %u out of bound [%u, %u]", (unsigned)wpr.seq, (unsigned)wpr.seq, (unsigned)_count - 1); } _state = MAVLINK_WPM_STATE_IDLE; send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR); _mavlink->send_statustext_critical("WPM: REJ. CMD: Req. WP was unexpected"); } } else if (_state == MAVLINK_WPM_STATE_IDLE) { if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST(_INT) ERROR: no transfer"); } _mavlink->send_statustext_critical("IGN MISSION_ITEM_REQUEST(_INT): No active transfer"); } else { if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST(_INT) ERROR: busy (state %d).", _state); } _mavlink->send_statustext_critical("WPM: REJ. CMD: Busy"); } } else { _mavlink->send_statustext_critical("WPM: REJ. CMD: partner id mismatch"); if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST(_INT) ERROR: rejected, partner ID mismatch"); } } } }
int MavlinkULog::handle_update(mavlink_channel_t channel) { static_assert(sizeof(ulog_stream_s::data) == MAVLINK_MSG_LOGGING_DATA_FIELD_DATA_LEN, "Invalid uorb ulog_stream.data length"); static_assert(sizeof(ulog_stream_s::data) == MAVLINK_MSG_LOGGING_DATA_ACKED_FIELD_DATA_LEN, "Invalid uorb ulog_stream.data length"); if (_waiting_for_initial_ack) { if (hrt_elapsed_time(&_last_sent_time) > 3e5) { PX4_WARN("no ack from logger (is it running?)"); return -1; } return 0; } // check if we're waiting for an ACK if (_last_sent_time) { bool check_for_updates = false; if (_ack_received) { _last_sent_time = 0; check_for_updates = true; } else { if (hrt_elapsed_time(&_last_sent_time) > ulog_stream_ack_s::ACK_TIMEOUT * 1000) { if (++_sent_tries > ulog_stream_ack_s::ACK_MAX_TRIES) { return -ETIMEDOUT; } else { PX4_DEBUG("re-sending ulog mavlink message (try=%i)", _sent_tries); _last_sent_time = hrt_absolute_time(); mavlink_logging_data_acked_t msg; msg.sequence = _ulog_data.sequence; msg.length = _ulog_data.length; msg.first_message_offset = _ulog_data.first_message_offset; msg.target_system = _target_system; msg.target_component = _target_component; memcpy(msg.data, _ulog_data.data, sizeof(msg.data)); mavlink_msg_logging_data_acked_send_struct(channel, &msg); } } } if (!check_for_updates) { return 0; } } bool updated = false; int ret = orb_check(_ulog_stream_sub, &updated); while (updated && !ret && _current_num_msgs < _max_num_messages) { orb_copy(ORB_ID(ulog_stream), _ulog_stream_sub, &_ulog_data); if (_ulog_data.flags & ulog_stream_s::FLAGS_NEED_ACK) { _sent_tries = 1; _last_sent_time = hrt_absolute_time(); lock(); _wait_for_ack_sequence = _ulog_data.sequence; _ack_received = false; unlock(); mavlink_logging_data_acked_t msg; msg.sequence = _ulog_data.sequence; msg.length = _ulog_data.length; msg.first_message_offset = _ulog_data.first_message_offset; msg.target_system = _target_system; msg.target_component = _target_component; memcpy(msg.data, _ulog_data.data, sizeof(msg.data)); mavlink_msg_logging_data_acked_send_struct(channel, &msg); } else { mavlink_logging_data_t msg; msg.sequence = _ulog_data.sequence; msg.length = _ulog_data.length; msg.first_message_offset = _ulog_data.first_message_offset; msg.target_system = _target_system; msg.target_component = _target_component; memcpy(msg.data, _ulog_data.data, sizeof(msg.data)); mavlink_msg_logging_data_send_struct(channel, &msg); } ++_current_num_msgs; ret = orb_check(_ulog_stream_sub, &updated); } //need to update the rate? hrt_abstime t = hrt_absolute_time(); if (t > _next_rate_check) { if (_current_num_msgs < _max_num_messages) { _current_rate_factor = _max_rate_factor * (float)_current_num_msgs / _max_num_messages; } else { _current_rate_factor = _max_rate_factor; } _current_num_msgs = 0; _next_rate_check = t + _rate_calculation_delta_t * 1.e6f; PX4_DEBUG("current rate=%.3f (max=%i msgs in %.3fs)", (double)_current_rate_factor, _max_num_messages, (double)_rate_calculation_delta_t); } return 0; }
void MavlinkMissionManager::handle_mission_item_both(const mavlink_message_t *msg) { // The mavlink_message could also contain a mavlink_mission_item_int_t. We ignore that here // and take care of it later in parse_mavlink_mission_item depending on _int_mode. mavlink_mission_item_t wp; mavlink_msg_mission_item_decode(msg, &wp); if (CHECK_SYSID_COMPID_MISSION(wp)) { if (_state == MAVLINK_WPM_STATE_GETLIST) { _time_last_recv = hrt_absolute_time(); if (wp.seq != _transfer_seq) { if (_verbose) { warnx("WPM: MISSION_ITEM ERROR: seq %u was not the expected %u", wp.seq, _transfer_seq); } /* don't send request here, it will be performed in eventloop after timeout */ return; } } else if (_state == MAVLINK_WPM_STATE_IDLE) { if (_verbose) { warnx("WPM: MISSION_ITEM ERROR: no transfer"); } _mavlink->send_statustext_critical("IGN MISSION_ITEM: No transfer"); return; } else { if (_verbose) { warnx("WPM: MISSION_ITEM ERROR: busy, state %i", _state); } _mavlink->send_statustext_critical("IGN MISSION_ITEM: Busy"); return; } struct mission_item_s mission_item = {}; int ret = parse_mavlink_mission_item(&wp, &mission_item); if (ret != OK) { if (_verbose) { warnx("WPM: MISSION_ITEM ERROR: seq %u invalid item", wp.seq); } _mavlink->send_statustext_critical("IGN MISSION_ITEM: Busy"); send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, ret); _state = MAVLINK_WPM_STATE_IDLE; _transfer_in_progress = false; return; } dm_item_t dm_item = DM_KEY_WAYPOINTS_OFFBOARD(_transfer_dataman_id); if (dm_write(dm_item, wp.seq, DM_PERSIST_POWER_ON_RESET, &mission_item, sizeof(struct mission_item_s)) != sizeof(struct mission_item_s)) { if (_verbose) { warnx("WPM: MISSION_ITEM ERROR: error writing seq %u to dataman ID %i", wp.seq, _transfer_dataman_id); } send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR); _mavlink->send_statustext_critical("Unable to write on micro SD"); _state = MAVLINK_WPM_STATE_IDLE; _transfer_in_progress = false; return; } /* waypoint marked as current */ if (wp.current) { _transfer_current_seq = wp.seq; } if (_verbose) { warnx("WPM: MISSION_ITEM seq %u received", wp.seq); } _transfer_seq = wp.seq + 1; if (_transfer_seq == _transfer_count) { /* got all new mission items successfully */ if (_verbose) { warnx("WPM: MISSION_ITEM got all %u items, current_seq=%u, changing state to MAVLINK_WPM_STATE_IDLE", _transfer_count, _transfer_current_seq); } _state = MAVLINK_WPM_STATE_IDLE; if (update_active_mission(_transfer_dataman_id, _transfer_count, _transfer_current_seq) == OK) { send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ACCEPTED); } else { send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR); } _transfer_in_progress = false; } else { /* request next item */ send_mission_request(_transfer_partner_sysid, _transfer_partner_compid, _transfer_seq); } } }
int ADC::init() { /* do calibration if supported */ #ifdef ADC_CR2_CAL rCR2 |= ADC_CR2_CAL; usleep(100); if (rCR2 & ADC_CR2_CAL) { return -1; } #endif /* arbitrarily configure all channels for 55 cycle sample time */ rSMPR1 = 0b00000011011011011011011011011011; rSMPR2 = 0b00011011011011011011011011011011; /* XXX for F2/4, might want to select 12-bit mode? */ rCR1 = 0; /* enable the temperature sensor / Vrefint channel if supported*/ rCR2 = #ifdef ADC_CR2_TSVREFE /* enable the temperature sensor in CR2 */ ADC_CR2_TSVREFE | #endif 0; #ifdef ADC_CCR_TSVREFE /* enable temperature sensor in CCR */ rCCR = ADC_CCR_TSVREFE; #endif /* configure for a single-channel sequence */ rSQR1 = 0; rSQR2 = 0; rSQR3 = 0; /* will be updated with the channel each tick */ /* power-cycle the ADC and turn it on */ rCR2 &= ~ADC_CR2_ADON; usleep(10); rCR2 |= ADC_CR2_ADON; usleep(10); rCR2 |= ADC_CR2_ADON; usleep(10); /* kick off a sample and wait for it to complete */ hrt_abstime now = hrt_absolute_time(); rCR2 |= ADC_CR2_SWSTART; while (!(rSR & ADC_SR_EOC)) { /* don't wait for more than 500us, since that means something broke - should reset here if we see this */ if ((hrt_absolute_time() - now) > 500) { DEVICE_LOG("sample timeout"); return -1; } } /* create the device node */ return CDev::init(); }
void controls_main(void) { struct pollfd fds[2]; /* DSM input */ fds[0].fd = dsm_init("/dev/ttyS0"); fds[0].events = POLLIN; /* S.bus input */ fds[1].fd = sbus_init("/dev/ttyS2"); fds[1].events = POLLIN; for (;;) { /* run this loop at ~100Hz */ poll(fds, 2, 10); /* * Gather R/C control inputs from supported sources. * * Note that if you're silly enough to connect more than * one control input source, they're going to fight each * other. Don't do that. */ bool locked = false; if (fds[0].revents & POLLIN) locked |= dsm_input(); if (fds[1].revents & POLLIN) locked |= sbus_input(); /* * If we don't have lock from one of the serial receivers, * look for PPM. It shares an input with S.bus, so there's * a possibility it will mis-parse an S.bus frame. * * XXX each S.bus frame will cause a PPM decoder interrupt * storm (lots of edges). It might be sensible to actually * disable the PPM decoder completely if we have an alternate * receiver lock. */ if (!locked) ppm_input(); /* * If we haven't seen any new control data in 200ms, assume we * have lost input and tell FMU. */ if ((hrt_absolute_time() - system_state.rc_channels_timestamp) > 200000) { /* set the number of channels to zero - no inputs */ system_state.rc_channels = 0; /* trigger an immediate report to the FMU */ system_state.fmu_report_due = true; } /* XXX do bypass mode, etc. here */ /* do PWM output updates */ mixer_tick(); } }
void Ekf2::task_main() { // subscribe to relevant topics _sensors_sub = orb_subscribe(ORB_ID(sensor_combined)); _gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position)); _airspeed_sub = orb_subscribe(ORB_ID(airspeed)); _params_sub = orb_subscribe(ORB_ID(parameter_update)); _optical_flow_sub = orb_subscribe(ORB_ID(optical_flow)); _range_finder_sub = orb_subscribe(ORB_ID(distance_sensor)); _vehicle_land_detected_sub = orb_subscribe(ORB_ID(vehicle_land_detected)); px4_pollfd_struct_t fds[2] = {}; fds[0].fd = _sensors_sub; fds[0].events = POLLIN; fds[1].fd = _params_sub; fds[1].events = POLLIN; // initialise parameter cache updateParams(); // initialize data structures outside of loop // because they will else not always be // properly populated sensor_combined_s sensors = {}; vehicle_gps_position_s gps = {}; airspeed_s airspeed = {}; optical_flow_s optical_flow = {}; distance_sensor_s range_finder = {}; vehicle_land_detected_s vehicle_land_detected = {}; while (!_task_should_exit) { int ret = px4_poll(fds, sizeof(fds) / sizeof(fds[0]), 1000); if (ret < 0) { // Poll error, sleep and try again usleep(10000); continue; } else if (ret == 0) { // Poll timeout or no new data, do nothing continue; } if (fds[1].revents & POLLIN) { // read from param to clear updated flag struct parameter_update_s update; orb_copy(ORB_ID(parameter_update), _params_sub, &update); updateParams(); // fetch sensor data in next loop continue; } else if (!(fds[0].revents & POLLIN)) { // no new data continue; } bool gps_updated = false; bool airspeed_updated = false; bool optical_flow_updated = false; bool range_finder_updated = false; bool vehicle_land_detected_updated = false; orb_copy(ORB_ID(sensor_combined), _sensors_sub, &sensors); // update all other topics if they have new data orb_check(_gps_sub, &gps_updated); if (gps_updated) { orb_copy(ORB_ID(vehicle_gps_position), _gps_sub, &gps); } orb_check(_airspeed_sub, &airspeed_updated); if (airspeed_updated) { orb_copy(ORB_ID(airspeed), _airspeed_sub, &airspeed); } orb_check(_optical_flow_sub, &optical_flow_updated); if (optical_flow_updated) { orb_copy(ORB_ID(optical_flow), _optical_flow_sub, &optical_flow); } orb_check(_range_finder_sub, &range_finder_updated); if (range_finder_updated) { orb_copy(ORB_ID(distance_sensor), _range_finder_sub, &range_finder); } // in replay mode we are getting the actual timestamp from the sensor topic hrt_abstime now = 0; if (_replay_mode) { now = sensors.timestamp; } else { now = hrt_absolute_time(); } // push imu data into estimator _ekf.setIMUData(now, sensors.gyro_integral_dt[0], sensors.accelerometer_integral_dt[0], &sensors.gyro_integral_rad[0], &sensors.accelerometer_integral_m_s[0]); // read mag data _ekf.setMagData(sensors.magnetometer_timestamp[0], &sensors.magnetometer_ga[0]); // read baro data _ekf.setBaroData(sensors.baro_timestamp[0], &sensors.baro_alt_meter[0]); // read gps data if available if (gps_updated) { struct gps_message gps_msg = {}; gps_msg.time_usec = gps.timestamp_position; gps_msg.lat = gps.lat; gps_msg.lon = gps.lon; gps_msg.alt = gps.alt; gps_msg.fix_type = gps.fix_type; gps_msg.eph = gps.eph; gps_msg.epv = gps.epv; gps_msg.sacc = gps.s_variance_m_s; gps_msg.time_usec_vel = gps.timestamp_velocity; gps_msg.vel_m_s = gps.vel_m_s; gps_msg.vel_ned[0] = gps.vel_n_m_s; gps_msg.vel_ned[1] = gps.vel_e_m_s; gps_msg.vel_ned[2] = gps.vel_d_m_s; gps_msg.vel_ned_valid = gps.vel_ned_valid; gps_msg.nsats = gps.satellites_used; //TODO add gdop to gps topic gps_msg.gdop = 0.0f; _ekf.setGpsData(gps.timestamp_position, &gps_msg); } // read airspeed data if available float eas2tas = airspeed.true_airspeed_m_s / airspeed.indicated_airspeed_m_s; if (airspeed_updated && airspeed.true_airspeed_m_s > 7.0f) { _ekf.setAirspeedData(airspeed.timestamp, &airspeed.true_airspeed_m_s, &eas2tas); } if (optical_flow_updated) { flow_message flow; flow.flowdata(0) = optical_flow.pixel_flow_x_integral; flow.flowdata(1) = optical_flow.pixel_flow_y_integral; flow.quality = optical_flow.quality; flow.gyrodata(0) = optical_flow.gyro_x_rate_integral; flow.gyrodata(1) = optical_flow.gyro_y_rate_integral; flow.gyrodata(2) = optical_flow.gyro_z_rate_integral; flow.dt = optical_flow.integration_timespan; if (PX4_ISFINITE(optical_flow.pixel_flow_y_integral) && PX4_ISFINITE(optical_flow.pixel_flow_x_integral)) { _ekf.setOpticalFlowData(optical_flow.timestamp, &flow); } } if (range_finder_updated) { _ekf.setRangeData(range_finder.timestamp, &range_finder.current_distance); } orb_check(_vehicle_land_detected_sub, &vehicle_land_detected_updated); if (vehicle_land_detected_updated) { orb_copy(ORB_ID(vehicle_land_detected), _vehicle_land_detected_sub, &vehicle_land_detected); _ekf.set_in_air_status(!vehicle_land_detected.landed); } // run the EKF update and output if (_ekf.update()) { // generate vehicle attitude quaternion data struct vehicle_attitude_s att = {}; _ekf.copy_quaternion(att.q); matrix::Quaternion<float> q(att.q[0], att.q[1], att.q[2], att.q[3]); // generate control state data control_state_s ctrl_state = {}; ctrl_state.timestamp = hrt_absolute_time(); ctrl_state.roll_rate = _lp_roll_rate.apply(sensors.gyro_rad_s[0]); ctrl_state.pitch_rate = _lp_pitch_rate.apply(sensors.gyro_rad_s[1]); ctrl_state.yaw_rate = _lp_yaw_rate.apply(sensors.gyro_rad_s[2]); // Velocity in body frame float velocity[3]; _ekf.get_velocity(velocity); Vector3f v_n(velocity); matrix::Dcm<float> R_to_body(q.inversed()); Vector3f v_b = R_to_body * v_n; ctrl_state.x_vel = v_b(0); ctrl_state.y_vel = v_b(1); ctrl_state.z_vel = v_b(2); // Local Position NED float position[3]; _ekf.get_position(position); ctrl_state.x_pos = position[0]; ctrl_state.y_pos = position[1]; ctrl_state.z_pos = position[2]; // Attitude quaternion ctrl_state.q[0] = q(0); ctrl_state.q[1] = q(1); ctrl_state.q[2] = q(2); ctrl_state.q[3] = q(3); // Acceleration data matrix::Vector<float, 3> acceleration = {&sensors.accelerometer_m_s2[0]}; float accel_bias[3]; _ekf.get_accel_bias(accel_bias); ctrl_state.x_acc = acceleration(0) - accel_bias[0]; ctrl_state.y_acc = acceleration(1) - accel_bias[1]; ctrl_state.z_acc = acceleration(2) - accel_bias[2]; // compute lowpass filtered horizontal acceleration acceleration = R_to_body.transpose() * acceleration; _acc_hor_filt = 0.95f * _acc_hor_filt + 0.05f * sqrtf(acceleration(0) * acceleration(0) + acceleration( 1) * acceleration(1)); ctrl_state.horz_acc_mag = _acc_hor_filt; // Airspeed - take airspeed measurement directly here as no wind is estimated if (PX4_ISFINITE(airspeed.indicated_airspeed_m_s) && hrt_absolute_time() - airspeed.timestamp < 1e6 && airspeed.timestamp > 0) { ctrl_state.airspeed = airspeed.indicated_airspeed_m_s; ctrl_state.airspeed_valid = true; } else { ctrl_state.airspeed_valid = false; } // publish control state data if (_control_state_pub == nullptr) { _control_state_pub = orb_advertise(ORB_ID(control_state), &ctrl_state); } else { orb_publish(ORB_ID(control_state), _control_state_pub, &ctrl_state); } // generate remaining vehicle attitude data att.timestamp = hrt_absolute_time(); matrix::Euler<float> euler(q); att.roll = euler(0); att.pitch = euler(1); att.yaw = euler(2); att.q[0] = q(0); att.q[1] = q(1); att.q[2] = q(2); att.q[3] = q(3); att.q_valid = true; att.rollspeed = sensors.gyro_rad_s[0]; att.pitchspeed = sensors.gyro_rad_s[1]; att.yawspeed = sensors.gyro_rad_s[2]; // publish vehicle attitude data if (_att_pub == nullptr) { _att_pub = orb_advertise(ORB_ID(vehicle_attitude), &att); } else { orb_publish(ORB_ID(vehicle_attitude), _att_pub, &att); } // generate vehicle local position data struct vehicle_local_position_s lpos = {}; float pos[3] = {}; float vel[3] = {}; lpos.timestamp = hrt_absolute_time(); // Position of body origin in local NED frame _ekf.get_position(pos); lpos.x = pos[0]; lpos.y = pos[1]; lpos.z = pos[2]; // Velocity of body origin in local NED frame (m/s) _ekf.get_velocity(vel); lpos.vx = vel[0]; lpos.vy = vel[1]; lpos.vz = vel[2]; // TODO: better status reporting lpos.xy_valid = _ekf.local_position_is_valid(); lpos.z_valid = true; lpos.v_xy_valid = _ekf.local_position_is_valid(); lpos.v_z_valid = true; // Position of local NED origin in GPS / WGS84 frame struct map_projection_reference_s ekf_origin = {}; // true if position (x, y) is valid and has valid global reference (ref_lat, ref_lon) _ekf.get_ekf_origin(&lpos.ref_timestamp, &ekf_origin, &lpos.ref_alt); lpos.xy_global = _ekf.global_position_is_valid(); lpos.z_global = true; // true if z is valid and has valid global reference (ref_alt) lpos.ref_lat = ekf_origin.lat_rad * 180.0 / M_PI; // Reference point latitude in degrees lpos.ref_lon = ekf_origin.lon_rad * 180.0 / M_PI; // Reference point longitude in degrees // The rotation of the tangent plane vs. geographical north lpos.yaw = att.yaw; float terrain_vpos; lpos.dist_bottom_valid = _ekf.get_terrain_vert_pos(&terrain_vpos); lpos.dist_bottom = terrain_vpos - pos[2]; // Distance to bottom surface (ground) in meters lpos.dist_bottom_rate = -vel[2]; // Distance to bottom surface (ground) change rate lpos.surface_bottom_timestamp = hrt_absolute_time(); // Time when new bottom surface found // TODO: uORB definition does not define what these variables are. We have assumed them to be horizontal and vertical 1-std dev accuracy in metres Vector3f pos_var, vel_var; _ekf.get_pos_var(pos_var); _ekf.get_vel_var(vel_var); lpos.eph = sqrt(pos_var(0) + pos_var(1)); lpos.epv = sqrt(pos_var(2)); // publish vehicle local position data if (_lpos_pub == nullptr) { _lpos_pub = orb_advertise(ORB_ID(vehicle_local_position), &lpos); } else { orb_publish(ORB_ID(vehicle_local_position), _lpos_pub, &lpos); } // generate and publish global position data struct vehicle_global_position_s global_pos = {}; if (_ekf.global_position_is_valid()) { global_pos.timestamp = hrt_absolute_time(); // Time of this estimate, in microseconds since system start global_pos.time_utc_usec = gps.time_utc_usec; // GPS UTC timestamp in microseconds double est_lat, est_lon; map_projection_reproject(&ekf_origin, lpos.x, lpos.y, &est_lat, &est_lon); global_pos.lat = est_lat; // Latitude in degrees global_pos.lon = est_lon; // Longitude in degrees global_pos.alt = -pos[2] + lpos.ref_alt; // Altitude AMSL in meters global_pos.vel_n = vel[0]; // Ground north velocity, m/s global_pos.vel_e = vel[1]; // Ground east velocity, m/s global_pos.vel_d = vel[2]; // Ground downside velocity, m/s global_pos.yaw = euler(2); // Yaw in radians -PI..+PI. global_pos.eph = sqrt(pos_var(0) + pos_var(1));; // Standard deviation of position estimate horizontally global_pos.epv = sqrt(pos_var(2)); // Standard deviation of position vertically // TODO: implement terrain estimator global_pos.terrain_alt = 0.0f; // Terrain altitude in m, WGS84 global_pos.terrain_alt_valid = false; // Terrain altitude estimate is valid // TODO use innovatun consistency check timouts to set this global_pos.dead_reckoning = false; // True if this position is estimated through dead-reckoning global_pos.pressure_alt = sensors.baro_alt_meter[0]; // Pressure altitude AMSL (m) if (_vehicle_global_position_pub == nullptr) { _vehicle_global_position_pub = orb_advertise(ORB_ID(vehicle_global_position), &global_pos); } else { orb_publish(ORB_ID(vehicle_global_position), _vehicle_global_position_pub, &global_pos); } } } else if (_replay_mode) { // in replay mode we have to tell the replay module not to wait for an update // we do this by publishing an attitude with zero timestamp struct vehicle_attitude_s att = {}; att.timestamp = 0; if (_att_pub == nullptr) { _att_pub = orb_advertise(ORB_ID(vehicle_attitude), &att); } else { orb_publish(ORB_ID(vehicle_attitude), _att_pub, &att); } } // publish estimator status struct estimator_status_s status = {}; status.timestamp = hrt_absolute_time(); _ekf.get_state_delayed(status.states); _ekf.get_covariances(status.covariances); _ekf.get_gps_check_status(&status.gps_check_fail_flags); _ekf.get_control_mode(&status.control_mode_flags); _ekf.get_filter_fault_status(&status.filter_fault_flags); if (_estimator_status_pub == nullptr) { _estimator_status_pub = orb_advertise(ORB_ID(estimator_status), &status); } else { orb_publish(ORB_ID(estimator_status), _estimator_status_pub, &status); } // Publish wind estimate struct wind_estimate_s wind_estimate = {}; wind_estimate.timestamp = hrt_absolute_time(); wind_estimate.windspeed_north = status.states[22]; wind_estimate.windspeed_east = status.states[23]; wind_estimate.covariance_north = status.covariances[22]; wind_estimate.covariance_east = status.covariances[23]; if (_wind_pub == nullptr) { _wind_pub = orb_advertise(ORB_ID(wind_estimate), &wind_estimate); } else { orb_publish(ORB_ID(wind_estimate), _wind_pub, &wind_estimate); } // publish estimator innovation data struct ekf2_innovations_s innovations = {}; innovations.timestamp = hrt_absolute_time(); _ekf.get_vel_pos_innov(&innovations.vel_pos_innov[0]); _ekf.get_mag_innov(&innovations.mag_innov[0]); _ekf.get_heading_innov(&innovations.heading_innov); _ekf.get_airspeed_innov(&innovations.airspeed_innov); _ekf.get_flow_innov(&innovations.flow_innov[0]); _ekf.get_hagl_innov(&innovations.hagl_innov); _ekf.get_vel_pos_innov_var(&innovations.vel_pos_innov_var[0]); _ekf.get_mag_innov_var(&innovations.mag_innov_var[0]); _ekf.get_heading_innov_var(&innovations.heading_innov_var); _ekf.get_airspeed_innov_var(&innovations.airspeed_innov_var); _ekf.get_flow_innov_var(&innovations.flow_innov_var[0]); _ekf.get_hagl_innov_var(&innovations.hagl_innov_var); if (_estimator_innovations_pub == nullptr) { _estimator_innovations_pub = orb_advertise(ORB_ID(ekf2_innovations), &innovations); } else { orb_publish(ORB_ID(ekf2_innovations), _estimator_innovations_pub, &innovations); } // save the declination to the EKF2_MAG_DECL parameter when a land event is detected if ((_params->mag_declination_source & (1 << 1)) && !_prev_landed && vehicle_land_detected.landed) { float decl_deg; _ekf.copy_mag_decl_deg(&decl_deg); _mag_declination_deg.set(decl_deg); } _prev_landed = vehicle_land_detected.landed; // publish replay message if in replay mode bool publish_replay_message = (bool)_param_record_replay_msg.get(); if (publish_replay_message) { struct ekf2_replay_s replay = {}; replay.time_ref = now; replay.gyro_integral_dt = sensors.gyro_integral_dt[0]; replay.accelerometer_integral_dt = sensors.accelerometer_integral_dt[0]; replay.magnetometer_timestamp = sensors.magnetometer_timestamp[0]; replay.baro_timestamp = sensors.baro_timestamp[0]; memcpy(&replay.gyro_integral_rad[0], &sensors.gyro_integral_rad[0], sizeof(replay.gyro_integral_rad)); memcpy(&replay.accelerometer_integral_m_s[0], &sensors.accelerometer_integral_m_s[0], sizeof(replay.accelerometer_integral_m_s)); memcpy(&replay.magnetometer_ga[0], &sensors.magnetometer_ga[0], sizeof(replay.magnetometer_ga)); replay.baro_alt_meter = sensors.baro_alt_meter[0]; // only write gps data if we had a gps update. if (gps_updated) { replay.time_usec = gps.timestamp_position; replay.time_usec_vel = gps.timestamp_velocity; replay.lat = gps.lat; replay.lon = gps.lon; replay.alt = gps.alt; replay.fix_type = gps.fix_type; replay.nsats = gps.satellites_used; replay.eph = gps.eph; replay.epv = gps.epv; replay.sacc = gps.s_variance_m_s; replay.vel_m_s = gps.vel_m_s; replay.vel_n_m_s = gps.vel_n_m_s; replay.vel_e_m_s = gps.vel_e_m_s; replay.vel_d_m_s = gps.vel_d_m_s; replay.vel_ned_valid = gps.vel_ned_valid; } else { // this will tell the logging app not to bother logging any gps replay data replay.time_usec = 0; } if (optical_flow_updated) { replay.flow_timestamp = optical_flow.timestamp; replay.flow_pixel_integral[0] = optical_flow.pixel_flow_x_integral; replay.flow_pixel_integral[1] = optical_flow.pixel_flow_y_integral; replay.flow_gyro_integral[0] = optical_flow.gyro_x_rate_integral; replay.flow_gyro_integral[1] = optical_flow.gyro_y_rate_integral; replay.flow_time_integral = optical_flow.integration_timespan; replay.flow_quality = optical_flow.quality; } else { replay.flow_timestamp = 0; } if (range_finder_updated) { replay.rng_timestamp = range_finder.timestamp; replay.range_to_ground = range_finder.current_distance; } else { replay.rng_timestamp = 0; } if (airspeed_updated) { replay.asp_timestamp = airspeed.timestamp; replay.indicated_airspeed_m_s = airspeed.indicated_airspeed_m_s; replay.true_airspeed_m_s = airspeed.true_airspeed_m_s; replay.true_airspeed_unfiltered_m_s = airspeed.true_airspeed_unfiltered_m_s; replay.air_temperature_celsius = airspeed.air_temperature_celsius; replay.confidence = airspeed.confidence; } else { replay.asp_timestamp = 0; } if (_replay_pub == nullptr) { _replay_pub = orb_advertise(ORB_ID(ekf2_replay), &replay); } else { orb_publish(ORB_ID(ekf2_replay), _replay_pub, &replay); } } } delete ekf2::instance; ekf2::instance = nullptr; }
void l_actuator_outputs(const struct listener *l) { struct actuator_outputs_s act_outputs; orb_id_t ids[] = { ORB_ID(actuator_outputs_0), ORB_ID(actuator_outputs_1), ORB_ID(actuator_outputs_2), ORB_ID(actuator_outputs_3) }; /* copy actuator data into local buffer */ orb_copy(ids[l->arg], *l->subp, &act_outputs); if (gcs_link) { mavlink_msg_servo_output_raw_send(MAVLINK_COMM_0, last_sensor_timestamp / 1000, l->arg /* port number */, act_outputs.output[0], act_outputs.output[1], act_outputs.output[2], act_outputs.output[3], act_outputs.output[4], act_outputs.output[5], act_outputs.output[6], act_outputs.output[7]); /* only send in HIL mode */ if (mavlink_hil_enabled && armed.armed) { /* translate the current syste state to mavlink state and mode */ uint8_t mavlink_state = 0; uint8_t mavlink_base_mode = 0; uint32_t mavlink_custom_mode = 0; get_mavlink_mode_and_state(&mavlink_state, &mavlink_base_mode, &mavlink_custom_mode); /* HIL message as per MAVLink spec */ /* scale / assign outputs depending on system type */ if (mavlink_system.type == MAV_TYPE_QUADROTOR) { mavlink_msg_hil_controls_send(chan, hrt_absolute_time(), ((act_outputs.output[0] - 900.0f) / 600.0f) / 2.0f, ((act_outputs.output[1] - 900.0f) / 600.0f) / 2.0f, ((act_outputs.output[2] - 900.0f) / 600.0f) / 2.0f, ((act_outputs.output[3] - 900.0f) / 600.0f) / 2.0f, -1, -1, -1, -1, mavlink_base_mode, 0); } else if (mavlink_system.type == MAV_TYPE_HEXAROTOR) { mavlink_msg_hil_controls_send(chan, hrt_absolute_time(), ((act_outputs.output[0] - 900.0f) / 600.0f) / 2.0f, ((act_outputs.output[1] - 900.0f) / 600.0f) / 2.0f, ((act_outputs.output[2] - 900.0f) / 600.0f) / 2.0f, ((act_outputs.output[3] - 900.0f) / 600.0f) / 2.0f, ((act_outputs.output[4] - 900.0f) / 600.0f) / 2.0f, ((act_outputs.output[5] - 900.0f) / 600.0f) / 2.0f, -1, -1, mavlink_base_mode, 0); } else if (mavlink_system.type == MAV_TYPE_OCTOROTOR) { mavlink_msg_hil_controls_send(chan, hrt_absolute_time(), ((act_outputs.output[0] - 900.0f) / 600.0f) / 2.0f, ((act_outputs.output[1] - 900.0f) / 600.0f) / 2.0f, ((act_outputs.output[2] - 900.0f) / 600.0f) / 2.0f, ((act_outputs.output[3] - 900.0f) / 600.0f) / 2.0f, ((act_outputs.output[4] - 900.0f) / 600.0f) / 2.0f, ((act_outputs.output[5] - 900.0f) / 600.0f) / 2.0f, ((act_outputs.output[6] - 900.0f) / 600.0f) / 2.0f, ((act_outputs.output[7] - 900.0f) / 600.0f) / 2.0f, mavlink_base_mode, 0); } else { mavlink_msg_hil_controls_send(chan, hrt_absolute_time(), (act_outputs.output[0] - 1500.0f) / 500.0f, (act_outputs.output[1] - 1500.0f) / 500.0f, (act_outputs.output[2] - 1500.0f) / 500.0f, (act_outputs.output[3] - 1000.0f) / 1000.0f, (act_outputs.output[4] - 1500.0f) / 500.0f, (act_outputs.output[5] - 1500.0f) / 500.0f, (act_outputs.output[6] - 1500.0f) / 500.0f, (act_outputs.output[7] - 1500.0f) / 500.0f, mavlink_base_mode, 0); } } } }
int test_mixer(int argc, char *argv[]) { /* * PWM limit structure */ pwm_limit_t pwm_limit; static bool should_arm = false; uint16_t r_page_servo_disarmed[output_max]; uint16_t r_page_servo_control_min[output_max]; uint16_t r_page_servo_control_max[output_max]; uint16_t r_page_servos[output_max]; uint16_t servo_predicted[output_max]; warnx("testing mixer"); char *filename = "/etc/mixers/IO_pass.mix"; if (argc > 1) filename = argv[1]; warnx("loading: %s", filename); char buf[2048]; load_mixer_file(filename, &buf[0], sizeof(buf)); unsigned loaded = strlen(buf); warnx("loaded: \n\"%s\"\n (%d chars)", &buf[0], loaded); /* load the mixer in chunks, like * in the case of a remote load, * e.g. on PX4IO. */ unsigned nused = 0; const unsigned chunk_size = 64; MixerGroup mixer_group(mixer_callback, 0); /* load at once test */ unsigned xx = loaded; mixer_group.load_from_buf(&buf[0], xx); warnx("complete buffer load: loaded %u mixers", mixer_group.count()); if (mixer_group.count() != 8) return 1; unsigned empty_load = 2; char empty_buf[2]; empty_buf[0] = ' '; empty_buf[1] = '\0'; mixer_group.reset(); mixer_group.load_from_buf(&empty_buf[0], empty_load); warnx("empty buffer load: loaded %u mixers, used: %u", mixer_group.count(), empty_load); if (empty_load != 0) return 1; /* FIRST mark the mixer as invalid */ bool mixer_ok = false; /* THEN actually delete it */ mixer_group.reset(); char mixer_text[256]; /* large enough for one mixer */ unsigned mixer_text_length = 0; unsigned transmitted = 0; warnx("transmitted: %d, loaded: %d", transmitted, loaded); while (transmitted < loaded) { unsigned text_length = (loaded - transmitted > chunk_size) ? chunk_size : loaded - transmitted; /* check for overflow - this would be really fatal */ if ((mixer_text_length + text_length + 1) > sizeof(mixer_text)) { bool mixer_ok = false; return 1; } /* append mixer text and nul-terminate */ memcpy(&mixer_text[mixer_text_length], &buf[transmitted], text_length); mixer_text_length += text_length; mixer_text[mixer_text_length] = '\0'; warnx("buflen %u, text:\n\"%s\"", mixer_text_length, &mixer_text[0]); /* process the text buffer, adding new mixers as their descriptions can be parsed */ unsigned resid = mixer_text_length; mixer_group.load_from_buf(&mixer_text[0], resid); /* if anything was parsed */ if (resid != mixer_text_length) { /* only set mixer ok if no residual is left over */ if (resid == 0) { mixer_ok = true; } else { /* not yet reached the end of the mixer, set as not ok */ mixer_ok = false; } warnx("used %u", mixer_text_length - resid); /* copy any leftover text to the base of the buffer for re-use */ if (resid > 0) memcpy(&mixer_text[0], &mixer_text[mixer_text_length - resid], resid); mixer_text_length = resid; } transmitted += text_length; } warnx("chunked load: loaded %u mixers", mixer_group.count()); if (mixer_group.count() != 8) return 1; /* execute the mixer */ float outputs[output_max]; unsigned mixed; const int jmax = 5; pwm_limit_init(&pwm_limit); should_arm = true; /* run through arming phase */ for (int i = 0; i < output_max; i++) { actuator_controls[i] = 0.1f; r_page_servo_disarmed[i] = PWM_LOWEST_MIN; r_page_servo_control_min[i] = PWM_DEFAULT_MIN; r_page_servo_control_max[i] = PWM_DEFAULT_MAX; } warnx("ARMING TEST: STARTING RAMP"); unsigned sleep_quantum_us = 10000; hrt_abstime starttime = hrt_absolute_time(); unsigned sleepcount = 0; while (hrt_elapsed_time(&starttime) < INIT_TIME_US + RAMP_TIME_US) { /* mix */ mixed = mixer_group.mix(&outputs[0], output_max); pwm_limit_calc(should_arm, mixed, r_page_servo_disarmed, r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit); //warnx("mixed %d outputs (max %d), values:", mixed, output_max); for (int i = 0; i < mixed; i++) { /* check mixed outputs to be zero during init phase */ if (hrt_elapsed_time(&starttime) < INIT_TIME_US && r_page_servos[i] != r_page_servo_disarmed[i]) { warnx("disarmed servo value mismatch"); return 1; } if (hrt_elapsed_time(&starttime) >= INIT_TIME_US && r_page_servos[i] + 1 <= r_page_servo_disarmed[i]) { warnx("ramp servo value mismatch"); return 1; } //printf("\t %d: %8.4f limited: %8.4f, servo: %d\n", i, outputs_unlimited[i], outputs[i], (int)r_page_servos[i]); } usleep(sleep_quantum_us); sleepcount++; if (sleepcount % 10 == 0) { printf("."); fflush(stdout); } } printf("\n"); warnx("ARMING TEST: NORMAL OPERATION"); for (int j = -jmax; j <= jmax; j++) { for (int i = 0; i < output_max; i++) { actuator_controls[i] = j/10.0f + 0.1f * i; r_page_servo_disarmed[i] = PWM_LOWEST_MIN; r_page_servo_control_min[i] = PWM_DEFAULT_MIN; r_page_servo_control_max[i] = PWM_DEFAULT_MAX; } /* mix */ mixed = mixer_group.mix(&outputs[0], output_max); pwm_limit_calc(should_arm, mixed, r_page_servo_disarmed, r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit); warnx("mixed %d outputs (max %d)", mixed, output_max); for (int i = 0; i < mixed; i++) { servo_predicted[i] = 1500 + outputs[i] * (r_page_servo_control_max[i] - r_page_servo_control_min[i]) / 2.0f; if (fabsf(servo_predicted[i] - r_page_servos[i]) > 2) { printf("\t %d: %8.4f predicted: %d, servo: %d\n", i, outputs[i], servo_predicted[i], (int)r_page_servos[i]); warnx("mixer violated predicted value"); return 1; } } } warnx("ARMING TEST: DISARMING"); starttime = hrt_absolute_time(); sleepcount = 0; should_arm = false; while (hrt_elapsed_time(&starttime) < 600000) { /* mix */ mixed = mixer_group.mix(&outputs[0], output_max); pwm_limit_calc(should_arm, mixed, r_page_servo_disarmed, r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit); //warnx("mixed %d outputs (max %d), values:", mixed, output_max); for (int i = 0; i < mixed; i++) { /* check mixed outputs to be zero during init phase */ if (r_page_servos[i] != r_page_servo_disarmed[i]) { warnx("disarmed servo value mismatch"); return 1; } //printf("\t %d: %8.4f limited: %8.4f, servo: %d\n", i, outputs_unlimited[i], outputs[i], (int)r_page_servos[i]); } usleep(sleep_quantum_us); sleepcount++; if (sleepcount % 10 == 0) { printf("."); fflush(stdout); } } printf("\n"); warnx("ARMING TEST: REARMING: STARTING RAMP"); starttime = hrt_absolute_time(); sleepcount = 0; should_arm = true; while (hrt_elapsed_time(&starttime) < 600000 + RAMP_TIME_US) { /* mix */ mixed = mixer_group.mix(&outputs[0], output_max); pwm_limit_calc(should_arm, mixed, r_page_servo_disarmed, r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit); //warnx("mixed %d outputs (max %d), values:", mixed, output_max); for (int i = 0; i < mixed; i++) { /* predict value */ servo_predicted[i] = 1500 + outputs[i] * (r_page_servo_control_max[i] - r_page_servo_control_min[i]) / 2.0f; /* check ramp */ if (hrt_elapsed_time(&starttime) < RAMP_TIME_US && (r_page_servos[i] + 1 <= r_page_servo_disarmed[i] || r_page_servos[i] > servo_predicted[i])) { warnx("ramp servo value mismatch"); return 1; } /* check post ramp phase */ if (hrt_elapsed_time(&starttime) > RAMP_TIME_US && fabsf(servo_predicted[i] - r_page_servos[i]) > 2) { printf("\t %d: %8.4f predicted: %d, servo: %d\n", i, outputs[i], servo_predicted[i], (int)r_page_servos[i]); warnx("mixer violated predicted value"); return 1; } //printf("\t %d: %8.4f limited: %8.4f, servo: %d\n", i, outputs_unlimited[i], outputs[i], (int)r_page_servos[i]); } usleep(sleep_quantum_us); sleepcount++; if (sleepcount % 10 == 0) { printf("."); fflush(stdout); } } printf("\n"); /* load multirotor at once test */ mixer_group.reset(); if (argc > 2) filename = argv[2]; else filename = "/etc/mixers/FMU_quad_w.mix"; load_mixer_file(filename, &buf[0], sizeof(buf)); loaded = strlen(buf); warnx("loaded: \n\"%s\"\n (%d chars)", &buf[0], loaded); unsigned mc_loaded = loaded; mixer_group.load_from_buf(&buf[0], mc_loaded); warnx("complete buffer load: loaded %u mixers", mixer_group.count()); if (mixer_group.count() != 5) { warnx("FAIL: Quad W mixer load failed"); return 1; } warnx("SUCCESS: No errors in mixer test"); }
void pwm_limit_calc(const bool armed, const unsigned num_channels, const uint16_t *disarmed_pwm, const uint16_t *min_pwm, const uint16_t *max_pwm, const float *output, uint16_t *effective_pwm, pwm_limit_t *limit) { /* first evaluate state changes */ switch (limit->state) { case PWM_LIMIT_STATE_INIT: if (armed) { /* set arming time for the first call */ if (limit->time_armed == 0) { limit->time_armed = hrt_absolute_time(); } if (hrt_elapsed_time(&limit->time_armed) >= INIT_TIME_US) { limit->state = PWM_LIMIT_STATE_OFF; } } break; case PWM_LIMIT_STATE_OFF: if (armed) { limit->state = PWM_LIMIT_STATE_RAMP; /* reset arming time, used for ramp timing */ limit->time_armed = hrt_absolute_time(); } break; case PWM_LIMIT_STATE_RAMP: if (!armed) { limit->state = PWM_LIMIT_STATE_OFF; } else if (hrt_elapsed_time(&limit->time_armed) >= RAMP_TIME_US) { limit->state = PWM_LIMIT_STATE_ON; } break; case PWM_LIMIT_STATE_ON: if (!armed) { limit->state = PWM_LIMIT_STATE_OFF; } break; default: break; } unsigned progress; /* then set effective_pwm based on state */ switch (limit->state) { case PWM_LIMIT_STATE_OFF: case PWM_LIMIT_STATE_INIT: for (unsigned i=0; i<num_channels; i++) { effective_pwm[i] = disarmed_pwm[i]; } break; case PWM_LIMIT_STATE_RAMP: { hrt_abstime diff = hrt_elapsed_time(&limit->time_armed); progress = diff * 10000 / RAMP_TIME_US; for (unsigned i=0; i<num_channels; i++) { uint16_t ramp_min_pwm; /* if a disarmed pwm value was set, blend between disarmed and min */ if (disarmed_pwm[i] > 0) { /* safeguard against overflows */ unsigned disarmed = disarmed_pwm[i]; if (disarmed > min_pwm[i]) { disarmed = min_pwm[i]; } unsigned disarmed_min_diff = min_pwm[i] - disarmed; ramp_min_pwm = disarmed + (disarmed_min_diff * progress) / 10000; } else { /* no disarmed pwm value set, choose min pwm */ ramp_min_pwm = min_pwm[i]; } effective_pwm[i] = output[i] * (max_pwm[i] - ramp_min_pwm)/2 + (max_pwm[i] + ramp_min_pwm)/2; /* last line of defense against invalid inputs */ if (effective_pwm[i] < ramp_min_pwm) { effective_pwm[i] = ramp_min_pwm; } else if (effective_pwm[i] > max_pwm[i]) { effective_pwm[i] = max_pwm[i]; } } } break; case PWM_LIMIT_STATE_ON: for (unsigned i=0; i<num_channels; i++) { effective_pwm[i] = output[i] * (max_pwm[i] - min_pwm[i])/2 + (max_pwm[i] + min_pwm[i])/2; /* last line of defense against invalid inputs */ if (effective_pwm[i] < min_pwm[i]) { effective_pwm[i] = min_pwm[i]; } else if (effective_pwm[i] > max_pwm[i]) { effective_pwm[i] = max_pwm[i]; } } break; default: break; } return; }
void Navigator::task_main() { _mavlink_fd = open(MAVLINK_LOG_DEVICE, 0); _geofence.setMavlinkFd(_mavlink_fd); /* Try to load the geofence: * if /fs/microsd/etc/geofence.txt load from this file * else clear geofence data in datamanager */ struct stat buffer; if (stat(GEOFENCE_FILENAME, &buffer) == 0) { warnx("Try to load geofence.txt"); _geofence.loadFromFile(GEOFENCE_FILENAME); } else { mavlink_log_info(_mavlink_fd, "No geofence set"); if (_geofence.clearDm() > 0) warnx("Geofence cleared"); else warnx("Could not clear geofence"); } /* do subscriptions */ _global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position)); _gps_pos_sub = orb_subscribe(ORB_ID(vehicle_gps_position)); _sensor_combined_sub = orb_subscribe(ORB_ID(sensor_combined)); _capabilities_sub = orb_subscribe(ORB_ID(navigation_capabilities)); _vstatus_sub = orb_subscribe(ORB_ID(vehicle_status)); _control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode)); _home_pos_sub = orb_subscribe(ORB_ID(home_position)); _onboard_mission_sub = orb_subscribe(ORB_ID(onboard_mission)); _offboard_mission_sub = orb_subscribe(ORB_ID(offboard_mission)); _param_update_sub = orb_subscribe(ORB_ID(parameter_update)); /* copy all topics first time */ vehicle_status_update(); vehicle_control_mode_update(); global_position_update(); gps_position_update(); sensor_combined_update(); home_position_update(); navigation_capabilities_update(); params_update(); /* rate limit position and sensor updates to 50 Hz */ orb_set_interval(_global_pos_sub, 20); orb_set_interval(_sensor_combined_sub, 20); hrt_abstime mavlink_open_time = 0; const hrt_abstime mavlink_open_interval = 500000; /* wakeup source(s) */ struct pollfd fds[8]; /* Setup of loop */ fds[0].fd = _global_pos_sub; fds[0].events = POLLIN; fds[1].fd = _home_pos_sub; fds[1].events = POLLIN; fds[2].fd = _capabilities_sub; fds[2].events = POLLIN; fds[3].fd = _vstatus_sub; fds[3].events = POLLIN; fds[4].fd = _control_mode_sub; fds[4].events = POLLIN; fds[5].fd = _param_update_sub; fds[5].events = POLLIN; fds[6].fd = _sensor_combined_sub; fds[6].events = POLLIN; fds[7].fd = _gps_pos_sub; fds[7].events = POLLIN; while (!_task_should_exit) { /* wait for up to 100ms for data */ int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100); if (pret == 0) { /* timed out - periodic check for _task_should_exit, etc. */ continue; } else if (pret < 0) { /* this is undesirable but not much we can do - might want to flag unhappy status */ warn("poll error %d, %d", pret, errno); continue; } perf_begin(_loop_perf); if (_mavlink_fd < 0 && hrt_absolute_time() > mavlink_open_time) { /* try to reopen the mavlink log device with specified interval */ mavlink_open_time = hrt_abstime() + mavlink_open_interval; _mavlink_fd = open(MAVLINK_LOG_DEVICE, 0); } static bool have_geofence_position_data = false; /* gps updated */ if (fds[7].revents & POLLIN) { gps_position_update(); if (_geofence.getSource() == Geofence::GF_SOURCE_GPS) { have_geofence_position_data = true; } } /* sensors combined updated */ if (fds[6].revents & POLLIN) { sensor_combined_update(); } /* parameters updated */ if (fds[5].revents & POLLIN) { params_update(); updateParams(); } /* vehicle control mode updated */ if (fds[4].revents & POLLIN) { vehicle_control_mode_update(); } /* vehicle status updated */ if (fds[3].revents & POLLIN) { vehicle_status_update(); } /* navigation capabilities updated */ if (fds[2].revents & POLLIN) { navigation_capabilities_update(); } /* home position updated */ if (fds[1].revents & POLLIN) { home_position_update(); } /* global position updated */ if (fds[0].revents & POLLIN) { global_position_update(); if (_geofence.getSource() == Geofence::GF_SOURCE_GLOBALPOS) { have_geofence_position_data = true; } } /* Check geofence violation */ static hrt_abstime last_geofence_check = 0; if (have_geofence_position_data && hrt_elapsed_time(&last_geofence_check) > GEOFENCE_CHECK_INTERVAL) { bool inside = _geofence.inside(_global_pos, _gps_pos, _sensor_combined.baro_alt_meter, _home_pos, _home_position_set); last_geofence_check = hrt_absolute_time(); have_geofence_position_data = false; if (!inside) { /* inform other apps via the mission result */ _geofence_result.geofence_violated = true; publish_geofence_result(); /* Issue a warning about the geofence violation once */ if (!_geofence_violation_warning_sent) { mavlink_log_critical(_mavlink_fd, "#audio: Geofence violation"); _geofence_violation_warning_sent = true; } } else { /* inform other apps via the mission result */ _geofence_result.geofence_violated = false; publish_geofence_result(); /* Reset the _geofence_violation_warning_sent field */ _geofence_violation_warning_sent = false; } } /* Do stuff according to navigation state set by commander */ switch (_vstatus.nav_state) { case vehicle_status_s::NAVIGATION_STATE_MANUAL: case vehicle_status_s::NAVIGATION_STATE_ACRO: case vehicle_status_s::NAVIGATION_STATE_ALTCTL: case vehicle_status_s::NAVIGATION_STATE_POSCTL: case vehicle_status_s::NAVIGATION_STATE_LAND: case vehicle_status_s::NAVIGATION_STATE_TERMINATION: case vehicle_status_s::NAVIGATION_STATE_OFFBOARD: _navigation_mode = nullptr; _can_loiter_at_sp = false; break; case vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION: _pos_sp_triplet_published_invalid_once = false; _navigation_mode = &_mission; break; case vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER: _pos_sp_triplet_published_invalid_once = false; _navigation_mode = &_loiter; break; case vehicle_status_s::NAVIGATION_STATE_AUTO_RCRECOVER: _pos_sp_triplet_published_invalid_once = false; if (_param_rcloss_obc.get() != 0) { _navigation_mode = &_rcLoss; } else { _navigation_mode = &_rtl; } break; case vehicle_status_s::NAVIGATION_STATE_AUTO_RTL: _pos_sp_triplet_published_invalid_once = false; _navigation_mode = &_rtl; break; case vehicle_status_s::NAVIGATION_STATE_AUTO_RTGS: /* Use complex data link loss mode only when enabled via param * otherwise use rtl */ _pos_sp_triplet_published_invalid_once = false; if (_param_datalinkloss_obc.get() != 0) { _navigation_mode = &_dataLinkLoss; } else { _navigation_mode = &_rtl; } break; case vehicle_status_s::NAVIGATION_STATE_AUTO_LANDENGFAIL: _pos_sp_triplet_published_invalid_once = false; _navigation_mode = &_engineFailure; break; case vehicle_status_s::NAVIGATION_STATE_AUTO_LANDGPSFAIL: _pos_sp_triplet_published_invalid_once = false; _navigation_mode = &_gpsFailure; break; default: _navigation_mode = nullptr; _can_loiter_at_sp = false; break; } /* iterate through navigation modes and set active/inactive for each */ for(unsigned int i = 0; i < NAVIGATOR_MODE_ARRAY_SIZE; i++) { _navigation_mode_array[i]->run(_navigation_mode == _navigation_mode_array[i]); } /* if nothing is running, set position setpoint triplet invalid once */ if (_navigation_mode == nullptr && !_pos_sp_triplet_published_invalid_once) { _pos_sp_triplet_published_invalid_once = true; _pos_sp_triplet.previous.valid = false; _pos_sp_triplet.current.valid = false; _pos_sp_triplet.next.valid = false; _pos_sp_triplet_updated = true; } if (_pos_sp_triplet_updated) { publish_position_setpoint_triplet(); _pos_sp_triplet_updated = false; } if (_mission_result_updated) { publish_mission_result(); _mission_result_updated = false; } perf_end(_loop_perf); } warnx("exiting."); _navigator_task = -1; _exit(0); }
/** * Transition from one failsafe state to another */ transition_result_t failsafe_state_transition(struct vehicle_status_s *status, failsafe_state_t new_failsafe_state) { transition_result_t ret = TRANSITION_DENIED; /* transition may be denied even if requested the same state because conditions may be changed */ if (status->failsafe_state == FAILSAFE_STATE_TERMINATION) { /* transitions from TERMINATION to other states not allowed */ if (new_failsafe_state == FAILSAFE_STATE_TERMINATION) { ret = TRANSITION_NOT_CHANGED; } } else { switch (new_failsafe_state) { case FAILSAFE_STATE_NORMAL: /* always allowed (except from TERMINATION state) */ ret = TRANSITION_CHANGED; break; case FAILSAFE_STATE_RTL: /* global position and home position required for RTL */ if (status->condition_global_position_valid && status->condition_home_position_valid) { status->set_nav_state = NAV_STATE_RTL; status->set_nav_state_timestamp = hrt_absolute_time(); ret = TRANSITION_CHANGED; } break; case FAILSAFE_STATE_LAND: /* at least relative altitude estimate required for landing */ if (status->condition_local_altitude_valid || status->condition_global_position_valid) { status->set_nav_state = NAV_STATE_LAND; status->set_nav_state_timestamp = hrt_absolute_time(); ret = TRANSITION_CHANGED; } break; case FAILSAFE_STATE_TERMINATION: /* always allowed */ ret = TRANSITION_CHANGED; break; default: break; } if (ret == TRANSITION_CHANGED) { if (status->failsafe_state != new_failsafe_state) { status->failsafe_state = new_failsafe_state; failsafe_state_changed = true; } else { ret = TRANSITION_NOT_CHANGED; } } } return ret; }
int MEASAirspeed::collect() { int ret = -EIO; /* read from the sensor */ uint8_t val[4] = {0, 0, 0, 0}; perf_begin(_sample_perf); ret = transfer(nullptr, 0, &val[0], 4); if (ret < 0) { perf_count(_comms_errors); perf_end(_sample_perf); return ret; } uint8_t status = (val[0] & 0xC0) >> 6; switch (status) { case 0: // Normal Operation. Good Data Packet break; case 1: // Reserved return -EAGAIN; case 2: // Stale Data. Data has been fetched since last measurement cycle. return -EAGAIN; case 3: // Fault Detected perf_count(_comms_errors); perf_end(_sample_perf); return -EAGAIN; } int16_t dp_raw = 0, dT_raw = 0; dp_raw = (val[0] << 8) + val[1]; /* mask the used bits */ dp_raw = 0x3FFF & dp_raw; dT_raw = (val[2] << 8) + val[3]; dT_raw = (0xFFE0 & dT_raw) >> 5; // dT max is almost certainly an invalid reading if (dT_raw == 2047) { perf_count(_comms_errors); return -EAGAIN; } float temperature = ((200.0f * dT_raw) / 2047) - 50; // Calculate differential pressure. As its centered around 8000 // and can go positive or negative const float P_min = -1.0f; const float P_max = 1.0f; const float PSI_to_Pa = 6894.757f; /* this equation is an inversion of the equation in the pressure transfer function figure on page 4 of the datasheet We negate the result so that positive differential pressures are generated when the bottom port is used as the static port on the pitot and top port is used as the dynamic port */ float diff_press_PSI = -((dp_raw - 0.1f * 16383) * (P_max - P_min) / (0.8f * 16383) + P_min); float diff_press_pa_raw = diff_press_PSI * PSI_to_Pa; // correct for 5V rail voltage if possible voltage_correction(diff_press_pa_raw, temperature); /* With the above calculation the MS4525 sensor will produce a positive number when the top port is used as a dynamic port and bottom port is used as the static port */ struct differential_pressure_s report; report.timestamp = hrt_absolute_time(); report.error_count = perf_event_count(_comms_errors); report.temperature = temperature; report.differential_pressure_filtered_pa = _filter.apply(diff_press_pa_raw) - _diff_pres_offset; report.differential_pressure_raw_pa = diff_press_pa_raw - _diff_pres_offset; report.device_id = _device_id.devid; if (_airspeed_pub != nullptr && !(_pub_blocked)) { /* publish it */ orb_publish(ORB_ID(differential_pressure), _airspeed_pub, &report); } ret = OK; perf_end(_sample_perf); return ret; }
void L3GD20::measure() { /* status register and data as read back from the device */ #pragma pack(push, 1) struct { uint8_t cmd; uint8_t temp; uint8_t status; int16_t x; int16_t y; int16_t z; } raw_report; #pragma pack(pop) gyro_report *report = &_reports[_next_report]; /* start the performance counter */ perf_begin(_sample_perf); /* fetch data from the sensor */ raw_report.cmd = ADDR_OUT_TEMP | DIR_READ | ADDR_INCREMENT; transfer((uint8_t *)&raw_report, (uint8_t *)&raw_report, sizeof(raw_report)); /* * 1) Scale raw value to SI units using scaling from datasheet. * 2) Subtract static offset (in SI units) * 3) Scale the statically calibrated values with a linear * dynamically obtained factor * * Note: the static sensor offset is the number the sensor outputs * at a nominally 'zero' input. Therefore the offset has to * be subtracted. * * Example: A gyro outputs a value of 74 at zero angular rate * the offset is 74 from the origin and subtracting * 74 from all measurements centers them around zero. */ report->timestamp = hrt_absolute_time(); /* swap x and y and negate y */ report->x_raw = raw_report.y; report->y_raw = ((raw_report.x == -32768) ? 32767 : -raw_report.x); report->z_raw = raw_report.z; report->x = ((report->x_raw * _gyro_range_scale) - _gyro_scale.x_offset) * _gyro_scale.x_scale; report->y = ((report->y_raw * _gyro_range_scale) - _gyro_scale.y_offset) * _gyro_scale.y_scale; report->z = ((report->z_raw * _gyro_range_scale) - _gyro_scale.z_offset) * _gyro_scale.z_scale; report->scaling = _gyro_range_scale; report->range_rad_s = _gyro_range_rad_s; /* post a report to the ring - note, not locked */ INCREMENT(_next_report, _num_reports); /* if we are running up against the oldest report, fix it */ if (_next_report == _oldest_report) INCREMENT(_oldest_report, _num_reports); /* notify anyone waiting for data */ poll_notify(POLLIN); /* publish for subscribers */ if (_gyro_topic > 0) orb_publish(ORB_ID(sensor_gyro), _gyro_topic, report); /* stop the perf counter */ perf_end(_sample_perf); }
/** check for a scheduled reboot */ static void check_reboot(void) { if (reboot_time != 0 && hrt_absolute_time() > reboot_time) { up_systemreset(); } }