void OutputBase::_set_angle_setpoints(const ControlData *control_data) { _cur_control_data = control_data; for (int i = 0; i < 3; ++i) { _stabilize[i] = control_data->stabilize_axis[i]; _angle_speeds[i] = 0.f; } switch (control_data->type) { case ControlData::Type::Angle: for (int i = 0; i < 3; ++i) { if (control_data->type_data.angle.is_speed[i]) { _angle_speeds[i] = control_data->type_data.angle.angles[i]; } else { _angle_setpoints[i] = control_data->type_data.angle.angles[i]; } } break; case ControlData::Type::LonLat: _handle_position_update(true); break; case ControlData::Type::Neutral: _angle_setpoints[0] = 0.f; _angle_setpoints[1] = 0.f; _angle_setpoints[2] = 0.f; break; } }
int OutputMavlink::update(const ControlData *control_data) { vehicle_command_s vehicle_command = {}; vehicle_command.timestamp = hrt_absolute_time(); vehicle_command.target_system = (uint8_t)_config.mavlink_sys_id; vehicle_command.target_component = (uint8_t)_config.mavlink_comp_id; if (control_data) { //got new command _set_angle_setpoints(control_data); vehicle_command.command = vehicle_command_s::VEHICLE_CMD_DO_MOUNT_CONFIGURE; vehicle_command.timestamp = hrt_absolute_time(); if (control_data->type == ControlData::Type::Neutral) { vehicle_command.param1 = vehicle_command_s::VEHICLE_MOUNT_MODE_NEUTRAL; } else { vehicle_command.param1 = vehicle_command_s::VEHICLE_MOUNT_MODE_MAVLINK_TARGETING; } if (_vehicle_command_pub) { orb_publish(ORB_ID(vehicle_command), _vehicle_command_pub, &vehicle_command); } else { _vehicle_command_pub = orb_advertise_queue(ORB_ID(vehicle_command), &vehicle_command, vehicle_command_s::ORB_QUEUE_LENGTH); } } if (!_vehicle_command_pub) { return 0; } _handle_position_update(); hrt_abstime t = hrt_absolute_time(); _calculate_output_angles(t); vehicle_command.timestamp = t; vehicle_command.command = vehicle_command_s::VEHICLE_CMD_DO_MOUNT_CONTROL; // vmount spec has roll, pitch on channels 0, 1, respectively; MAVLink spec has roll, pitch on channels 1, 0, respectively // vmount uses radians, MAVLink uses degrees vehicle_command.param1 = (_angle_outputs[1] + _config.pitch_offset) * M_RAD_TO_DEG_F; vehicle_command.param2 = (_angle_outputs[0] + _config.roll_offset) * M_RAD_TO_DEG_F; vehicle_command.param3 = (_angle_outputs[2] + _config.yaw_offset) * M_RAD_TO_DEG_F; orb_publish(ORB_ID(vehicle_command), _vehicle_command_pub, &vehicle_command); _last_update = t; return 0; }