#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>
Go to the source code of this file.
◆ UavcanNode
◆ instantiate_converter()
◆ NodeMemoryPoolSize
constexpr unsigned NodeMemoryPoolSize = 16384 |
|
constexpr |