#include <iostream>
#include <math.h>
#include <deque>
#include <random>
#include <sys/socket.h>
#include <netinet/in.h>
#include <sdf/sdf.hh>
#include <stdio.h>
#include <boost/bind.hpp>
#include <Eigen/Eigen>
#include <gazebo/common/common.hh>
#include <gazebo/common/Plugin.hh>
#include <gazebo/gazebo.hh>
#include <gazebo/physics/physics.hh>
#include "ignition/math/Vector3.hh"
#include "gazebo/transport/transport.hh"
#include "gazebo/msgs/msgs.hh"
#include "common/mavlink.h"
#include "common.h"
#include "CommandMotorSpeed.pb.h"
#include "Imu.pb.h"
#include "OpticalFlow.pb.h"
#include "Lidar.pb.h"
Go to the source code of this file.
Classes | |
class | gazebo::GazeboMavlinkInterface |
Namespaces | |
namespace | gazebo |
Typedefs | |
typedef const boost::shared_ptr< const gz_mav_msgs::CommandMotorSpeed > | gazebo::CommandMotorSpeedPtr |
typedef const boost::shared_ptr< const gz_sensor_msgs::Imu > | gazebo::ImuPtr |
typedef const boost::shared_ptr< const lidar_msgs::msgs::lidar > | gazebo::LidarPtr |
typedef const boost::shared_ptr< const opticalFlow_msgs::msgs::opticalFlow > | gazebo::OpticalFlowPtr |
Variables | |
static const std::string | gazebo::kDefaultImuTopic = "/imu" |
static const std::string | gazebo::kDefaultLidarTopic = "/lidar/link/lidar" |
static const uint32_t | kDefaultMavlinkUdpPort = 14560 |
static const std::string | gazebo::kDefaultMotorVelocityReferencePubTopic = "/gazebo/command/motor_speed" |
static const std::string | gazebo::kDefaultOpticalFlowTopic = "/camera/link/opticalFlow" |
static const uint8_t | mavlink_message_crcs [256] = MAVLINK_MESSAGE_CRCS |
static const uint8_t | mavlink_message_lengths [256] = MAVLINK_MESSAGE_LENGTHS |
const uint32_t kDefaultMavlinkUdpPort = 14560 [static] |
Definition at line 52 of file gazebo_mavlink_interface.h.
const uint8_t mavlink_message_crcs[256] = MAVLINK_MESSAGE_CRCS [static] |
Definition at line 50 of file gazebo_mavlink_interface.h.
const uint8_t mavlink_message_lengths[256] = MAVLINK_MESSAGE_LENGTHS [static] |
Definition at line 49 of file gazebo_mavlink_interface.h.