Paparazzi UAS  v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
jevois_mavlink.c File Reference
#include "modules/sensors/cameras/jevois_mavlink.h"
#include <stdio.h>
#include <mavlink/mavlink_types.h>
#include "mavlink/paparazzi/mavlink.h"
#include "modules/imu/imu.h"
#include "autopilot.h"
#include "generated/modules.h"
#include "modules/core/abi.h"
#include "modules/core/abi_sender_ids.h"
#include "std.h"
#include "modules/datalink/telemetry.h"
#include "filters/low_pass_filter.h"
#include "state.h"
#include "mcu_periph/sys_time.h"
+ Include dependency graph for jevois_mavlink.c:

Go to the source code of this file.

Data Structures

struct  visual_target_struct
 
struct  vision_relative_position_struct
 

Macros

#define DEBUG_PRINT   printf
 
#define MAVLINK_SYSID   1
 
#define JEVOIS_MAVLINK_ABI_ID   34
 

Functions

static void mavlink_send_heartbeat (void)
 
static void mavlink_send_attitude (void)
 
static void mavlink_send_highres_imu (void)
 
static void mavlink_send_set_mode (void)
 
void jevois_mavlink_filter_periodic (void)
 
void jevois_mavlink_filter_init (void)
 
static void send_jevois_mavlink_visual_target (struct transport_tx *trans, struct link_device *dev)
 
static void send_jevois_mavlink_visual_position (struct transport_tx *trans, struct link_device *dev)
 
void jevois_mavlink_init (void)
 
void jevois_mavlink_periodic (void)
 
void jevois_mavlink_event (void)
 

Variables

mavlink_system_t mavlink_system
 
struct visual_target_struct jevois_visual_target = {false, 0, 0, 0, 0, 0, 0}
 
struct vision_relative_position_struct jevois_vision_position = {false, 0, 0.0f, 0.0f, 0.0f}
 
Butterworth2LowPass_int ax_filtered
 
Butterworth2LowPass_int ay_filtered
 
Butterworth2LowPass_int az_filtered
 

Detailed Description

Author
MAVLab Send sensor data to jevois and read commands from jevois

Definition in file jevois_mavlink.c.


Data Structure Documentation

◆ visual_target_struct

struct visual_target_struct

Definition at line 70 of file jevois_mavlink.c.

Data Fields
int count
int h
int quality
int received
int source
int w
int x
int y

◆ vision_relative_position_struct

struct vision_relative_position_struct

Definition at line 123 of file detect_gate.c.

Data Fields
int cnt
int received
float x
float y
float z

Macro Definition Documentation

◆ DEBUG_PRINT

#define DEBUG_PRINT   printf

Definition at line 29 of file jevois_mavlink.c.

◆ JEVOIS_MAVLINK_ABI_ID

#define JEVOIS_MAVLINK_ABI_ID   34

Definition at line 177 of file jevois_mavlink.c.

◆ MAVLINK_SYSID

#define MAVLINK_SYSID   1

Definition at line 54 of file jevois_mavlink.c.

Function Documentation

◆ jevois_mavlink_event()

◆ jevois_mavlink_filter_init()

void jevois_mavlink_filter_init ( void  )

Definition at line 107 of file jevois_mavlink.c.

References ax_filtered, ay_filtered, az_filtered, imu, and init_butterworth_2_low_pass_int().

Referenced by jevois_mavlink_init().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ jevois_mavlink_filter_periodic()

void jevois_mavlink_filter_periodic ( void  )

Definition at line 99 of file jevois_mavlink.c.

References ax_filtered, ay_filtered, az_filtered, imu, and update_butterworth_2_low_pass_int().

+ Here is the call graph for this function:

◆ jevois_mavlink_init()

void jevois_mavlink_init ( void  )

◆ jevois_mavlink_periodic()

void jevois_mavlink_periodic ( void  )

Definition at line 168 of file jevois_mavlink.c.

References mavlink_send_attitude(), mavlink_send_heartbeat(), mavlink_send_highres_imu(), and mavlink_send_set_mode().

+ Here is the call graph for this function:

◆ mavlink_send_attitude()

static void mavlink_send_attitude ( void  )
static

Definition at line 294 of file jevois_mavlink.c.

References get_sys_time_msec(), MAVLinkSendMessage, p, stateGetBodyRates_f(), and stateGetNedToBodyEulers_f().

Referenced by jevois_mavlink_periodic().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ mavlink_send_heartbeat()

static void mavlink_send_heartbeat ( void  )
static

Definition at line 318 of file jevois_mavlink.c.

References MAVLinkSendMessage.

Referenced by jevois_mavlink_periodic().

+ Here is the caller graph for this function:

◆ mavlink_send_highres_imu()

static void mavlink_send_highres_imu ( void  )
static

Definition at line 330 of file jevois_mavlink.c.

References ax_filtered, ay_filtered, az_filtered, get_butterworth_2_low_pass_int(), get_sys_time_msec(), MAVLinkSendMessage, p, stateGetBodyRates_f(), and stateGetNedToBodyEulers_f().

Referenced by jevois_mavlink_periodic().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ mavlink_send_set_mode()

static void mavlink_send_set_mode ( void  )
static

Definition at line 308 of file jevois_mavlink.c.

References get_sys_time_msec(), and MAVLinkSendMessage.

Referenced by jevois_mavlink_periodic().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ send_jevois_mavlink_visual_position()

static void send_jevois_mavlink_visual_position ( struct transport_tx *  trans,
struct link_device *  dev 
)
static

◆ send_jevois_mavlink_visual_target()

static void send_jevois_mavlink_visual_target ( struct transport_tx *  trans,
struct link_device *  dev 
)
static

Definition at line 120 of file jevois_mavlink.c.

References visual_target_struct::count, dev, h(), visual_target_struct::h, jevois_visual_target, visual_target_struct::received, s, visual_target_struct::source, visual_target_struct::w, visual_target_struct::x, and visual_target_struct::y.

Referenced by jevois_mavlink_init().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

Variable Documentation

◆ ax_filtered

◆ ay_filtered

◆ az_filtered

◆ jevois_vision_position

struct vision_relative_position_struct jevois_vision_position = {false, 0, 0.0f, 0.0f, 0.0f}

◆ jevois_visual_target

struct visual_target_struct jevois_visual_target = {false, 0, 0, 0, 0, 0, 0}

◆ mavlink_system

mavlink_system_t mavlink_system

Definition at line 51 of file jevois_mavlink.c.

Referenced by jevois_mavlink_init().