29 #define DEBUG_PRINT printf
37 #include <mavlink/mavlink_types.h>
38 #include "mavlink/paparazzi/mavlink.h"
42 #include "generated/modules.h"
54 #define MAVLINK_SYSID 1
130 pprz_msg_send_VISUALTARGET(trans,
dev, AC_ID, &cnt,
131 &tx, &ty, &w, &
h, &
s);
141 pprz_msg_send_VISION_POSITION_ESTIMATE(trans,
dev, AC_ID,
176 #ifndef JEVOIS_MAVLINK_ABI_ID
177 #define JEVOIS_MAVLINK_ABI_ID 34
184 mavlink_message_t
msg;
190 if (mavlink_parse_char(MAVLINK_COMM_1, c, &
msg, &
status)) {
193 case MAVLINK_MSG_ID_HEARTBEAT: {
201 case MAVLINK_MSG_ID_DEBUG: {
202 mavlink_debug_t jevois_mavlink_debug;
203 mavlink_msg_debug_decode(&
msg, &jevois_mavlink_debug);
205 DEBUG_PRINT(
"[jevois mavlink] debug value is %f\n", jevois_mavlink_debug.value);
206 DEBUG_PRINT(
"[jevois mavlink] debug ind is %d\n", jevois_mavlink_debug.ind);
209 case MAVLINK_MSG_ID_HIGHRES_IMU: {
210 mavlink_highres_imu_t jevois_mavlink_visual_target;
211 mavlink_msg_highres_imu_decode(&
msg, &jevois_mavlink_visual_target);
231 DEBUG_PRINT(
"[jevois mavlink] VISUAL_DETECTION %f,%f\n", jevois_mavlink_visual_target.xacc,
232 jevois_mavlink_visual_target.yacc);
237 case MAVLINK_MSG_ID_MANUAL_SETPOINT: {
238 mavlink_manual_setpoint_t jevois_mavlink_manual_setpoint;
239 mavlink_msg_manual_setpoint_decode(&
msg, &jevois_mavlink_manual_setpoint);
242 jevois_mavlink_manual_setpoint.roll,
243 jevois_mavlink_manual_setpoint.pitch,
244 jevois_mavlink_manual_setpoint.yaw);
246 DEBUG_PRINT(
"[jevois mavlink] phi_cmd = %f\n", DegOfRad(jevois_mavlink_manual_setpoint.roll));
247 DEBUG_PRINT(
"[jevois mavlink] theta_cmd = %f\n", DegOfRad(jevois_mavlink_manual_setpoint.pitch));
248 DEBUG_PRINT(
"[jevois mavlink] psi_cmd = %f\n", DegOfRad(jevois_mavlink_manual_setpoint.yaw));
249 DEBUG_PRINT(
"[jevois mavlink] alt_cmd = %f\n", jevois_mavlink_manual_setpoint.thrust);
255 case MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE: {
256 mavlink_vision_position_estimate_t jevois_mavlink_vision_position_estimate;
257 mavlink_msg_vision_position_estimate_decode(&
msg, &jevois_mavlink_vision_position_estimate);
296 mavlink_msg_attitude_send(MAVLINK_COMM_0,
310 mavlink_msg_set_mode_send(MAVLINK_COMM_0,
320 mavlink_msg_heartbeat_send(MAVLINK_COMM_0,
323 MAV_MODE_FLAG_AUTO_ENABLED,
325 MAV_STATE_CALIBRATING);
332 mavlink_msg_highres_imu_send(MAVLINK_COMM_0,
static void h(const real32_T x[7], const real32_T q[4], real32_T y[6])
Main include for ABI (AirBorneInterface).
Convenience defines for ABI sender IDs.
Core autopilot interface common to all firmwares.
uint32_t get_sys_time_msec(void)
Get the time in milliseconds since startup.
static struct FloatEulers * stateGetNedToBodyEulers_f(void)
Get vehicle body attitude euler angles (float).
static struct FloatRates * stateGetBodyRates_f(void)
Get vehicle body angular rate (float).
uint8_t msg[10]
Buffer used for general comunication over SPI (out buffer)
struct Imu imu
global IMU state
Inertial Measurement Unit interface.
void jevois_mavlink_filter_init(void)
void jevois_mavlink_init(void)
void jevois_mavlink_event(void)
mavlink_system_t mavlink_system
void jevois_mavlink_periodic(void)
#define JEVOIS_MAVLINK_ABI_ID
void jevois_mavlink_filter_periodic(void)
static void mavlink_send_set_mode(void)
struct vision_relative_position_struct jevois_vision_position
struct visual_target_struct jevois_visual_target
static void send_jevois_mavlink_visual_target(struct transport_tx *trans, struct link_device *dev)
static void mavlink_send_highres_imu(void)
Butterworth2LowPass_int ay_filtered
static void mavlink_send_attitude(void)
Butterworth2LowPass_int ax_filtered
Butterworth2LowPass_int az_filtered
static void send_jevois_mavlink_visual_position(struct transport_tx *trans, struct link_device *dev)
static void mavlink_send_heartbeat(void)
Simple first order low pass filter with bilinear transform.
static int32_t get_butterworth_2_low_pass_int(Butterworth2LowPass_int *filter)
Get current value of the second order Butterworth low pass filter(fixed point version).
static void init_butterworth_2_low_pass_int(Butterworth2LowPass_int *filter, float cut_off, float sample_time, int32_t value)
Init a second order Butterworth filter.
static int32_t update_butterworth_2_low_pass_int(Butterworth2LowPass_int *filter, int32_t value)
Update second order Butterworth low pass filter state with a new value(fixed point version).
#define MAVLinkSendMessage()
#define MAVLinkChAvailable()
struct mavlink_heartbeat heartbeat
API to get/set the generic vehicle states.
static const struct usb_device_descriptor dev
Architecture independent timing functions.
int8_t register_periodic_telemetry(struct periodic_telemetry *_pt, uint8_t _id, telemetry_cb _cb)
Register a telemetry callback function.
Periodic telemetry system header (includes downlink utility and generated code).
#define DefaultPeriodic
Set default periodic telemetry.
unsigned short uint16_t
Typedef defining 16 bit unsigned short type.
short int16_t
Typedef defining 16 bit short type.
unsigned char uint8_t
Typedef defining 8 bit unsigned char type.