Classes | Typedefs | Functions | Variables
converters.hpp File Reference
#include <ros/ros.h>
#include <sensor_msgs/Imu.h>
#include <sensor_msgs/NavSatFix.h>
#include <sensor_msgs/Joy.h>
#include <sensor_msgs/MagneticField.h>
#include <sensor_msgs/BatteryState.h>
#include <std_msgs/Bool.h>
#include <std_msgs/UInt8.h>
#include <std_msgs/Float32.h>
#include <geometry_msgs/Twist.h>
#include <mavros_msgs/BatteryStatus.h>
#include <mavros_msgs/ESCTelemetryItem.h>
#include <mavros_msgs/ESCStatusItem.h>
#include <iostream>
#include <memory>
#include <string>
#include <uavcan/uavcan.hpp>
#include <uavcan/equipment/actuator/ArrayCommand.hpp>
#include <uavcan/equipment/ahrs/MagneticFieldStrength.hpp>
#include <uavcan/equipment/ahrs/RawIMU.hpp>
#include <uavcan/equipment/ahrs/Solution.hpp>
#include <uavcan/equipment/air_data/RawAirData.hpp>
#include <uavcan/equipment/air_data/StaticPressure.hpp>
#include <uavcan/equipment/air_data/StaticTemperature.hpp>
#include <uavcan/equipment/esc/RawCommand.hpp>
#include <uavcan/equipment/esc/Status.hpp>
#include <uavcan/equipment/gnss/Fix2.hpp>
#include <uavcan/equipment/ice/FuelTankStatus.hpp>
#include <uavcan/equipment/ice/reciprocating/Status.hpp>
#include <uavcan/equipment/power/CircuitStatus.hpp>
#include <uavcan/equipment/power/BatteryInfo.hpp>
#include <uavcan/equipment/safety/ArmingStatus.hpp>
Include dependency graph for converters.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  AhrsSolutionUavcanToRos
 
class  ArmUavcanToRos
 
class  ArrayCommandUavcanToRos
 
class  BaroStaticPressureRosToUavcan
 
class  BaroStaticTemperatureRosToUavcan
 
class  BatteryInfoRosToUavcan
 
class  CircuitStatusUavcanToRos
 
class  Converter
 
class  DiffPressureRosToUavcan
 
class  EscStatusRosToUavcan
 
class  EscStatusUavcanToRos
 
class  GpsRosToUavcan
 
class  IceFuelTankStatusRosToUavcan
 
class  IceReciprocatingStatusRosToUavcan
 
class  ImuRosToUavcan
 
class  MagnetometerRosToUavcan
 
class  RawCommandUavcanToRos
 
class  RosToUavcanConverter< IN_ROS, OUT_UAVCAN >
 
class  UavcanToRosConverter< IN_UAVCAN, OUT_ROS >
 

Typedefs

typedef uavcan::Node< NodeMemoryPoolSizeUavcanNode
 

Functions

std::unique_ptr< Converterinstantiate_converter (std::string converter_name, ros::NodeHandle &ros_node, UavcanNode &uavcan_node, const char *ros_topic)
 

Variables

constexpr unsigned NodeMemoryPoolSize = 16384
 

Typedef Documentation

◆ UavcanNode

Definition at line 58 of file converters.hpp.

Function Documentation

◆ instantiate_converter()

std::unique_ptr<Converter> instantiate_converter ( std::string  converter_name,
ros::NodeHandle ros_node,
UavcanNode uavcan_node,
const char *  ros_topic 
)

Definition at line 223 of file converters.cpp.

Variable Documentation

◆ NodeMemoryPoolSize

constexpr unsigned NodeMemoryPoolSize = 16384
constexpr

Definition at line 57 of file converters.hpp.



uavcan_communicator
Author(s):
autogenerated on Fri Dec 13 2024 03:10:03