#include <random>
#include <Eigen/Core>
#include <gazebo/common/Plugin.hh>
#include <gazebo/common/common.hh>
#include <gazebo/gazebo.hh>
#include <gazebo/physics/physics.hh>
#include "gazebo/msgs/msgs.hh"
#include <mav_msgs/default_topics.h>
#include <ros/callback_queue.h>
#include <ros/ros.h>
#include <tf/transform_broadcaster.h>
#include "ConnectGazeboToRosTopic.pb.h"
#include "ConnectRosToGazeboTopic.pb.h"
#include "Actuators.pb.h"
#include "CommandMotorSpeed.pb.h"
#include "Float32.pb.h"
#include "FluidPressure.pb.h"
#include "Imu.pb.h"
#include "JointState.pb.h"
#include "MagneticField.pb.h"
#include "NavSatFix.pb.h"
#include "Odometry.pb.h"
#include "PoseWithCovarianceStamped.pb.h"
#include "RollPitchYawrateThrust.pb.h"
#include "TransformStamped.pb.h"
#include "TransformStampedWithFrameIds.pb.h"
#include "TwistStamped.pb.h"
#include "Vector3dStamped.pb.h"
#include "WindSpeed.pb.h"
#include "WrenchStamped.pb.h"
#include <geometry_msgs/Point.h>
#include <geometry_msgs/PointStamped.h>
#include <geometry_msgs/Pose.h>
#include <geometry_msgs/PoseWithCovarianceStamped.h>
#include <geometry_msgs/TransformStamped.h>
#include <geometry_msgs/TwistStamped.h>
#include <geometry_msgs/WrenchStamped.h>
#include <mav_msgs/Actuators.h>
#include <mav_msgs/RollPitchYawrateThrust.h>
#include <nav_msgs/Odometry.h>
#include <rotors_comm/WindSpeed.h>
#include <sensor_msgs/FluidPressure.h>
#include <sensor_msgs/Imu.h>
#include <sensor_msgs/JointState.h>
#include <sensor_msgs/MagneticField.h>
#include <sensor_msgs/NavSatFix.h>
#include <std_msgs/Float32.h>
#include "rotors_gazebo_plugins/common.h"
Go to the source code of this file.
Classes | |
class | gazebo::GazeboRosInterfacePlugin |
ROS interface plugin for Gazebo. More... | |
Namespaces | |
namespace | gazebo |
Typedefs | |
typedef const boost::shared_ptr< const gz_std_msgs::ConnectGazeboToRosTopic > | gazebo::GzConnectGazeboToRosTopicMsgPtr |
typedef const boost::shared_ptr< const gz_std_msgs::ConnectRosToGazeboTopic > | gazebo::GzConnectRosToGazeboTopicMsgPtr |
typedef const boost::shared_ptr< const gz_std_msgs::Float32 > | gazebo::GzFloat32MsgPtr |
typedef const boost::shared_ptr< const gz_sensor_msgs::FluidPressure > | gazebo::GzFluidPressureMsgPtr |
typedef const boost::shared_ptr< const gz_sensor_msgs::Imu > | gazebo::GzImuPtr |
typedef const boost::shared_ptr< const gz_sensor_msgs::JointState > | gazebo::GzJointStateMsgPtr |
typedef const boost::shared_ptr< const gz_sensor_msgs::MagneticField > | gazebo::GzMagneticFieldMsgPtr |
typedef const boost::shared_ptr< const gz_sensor_msgs::NavSatFix > | gazebo::GzNavSatFixPtr |
typedef const boost::shared_ptr< const gz_geometry_msgs::Odometry > | gazebo::GzOdometryMsgPtr |
typedef const boost::shared_ptr< const gazebo::msgs::Pose > | gazebo::GzPoseMsgPtr |
typedef const boost::shared_ptr< const gz_geometry_msgs::PoseWithCovarianceStamped > | gazebo::GzPoseWithCovarianceStampedMsgPtr |
typedef const boost::shared_ptr< const gz_mav_msgs::RollPitchYawrateThrust > | gazebo::GzRollPitchYawrateThrustPtr |
typedef const boost::shared_ptr< const gz_geometry_msgs::TransformStamped > | gazebo::GzTransformStampedMsgPtr |
typedef const boost::shared_ptr< const gz_geometry_msgs::TransformStampedWithFrameIds > | gazebo::GzTransformStampedWithFrameIdsMsgPtr |
typedef const boost::shared_ptr< const gz_geometry_msgs::TwistStamped > | gazebo::GzTwistStampedMsgPtr |
typedef const boost::shared_ptr< const gz_geometry_msgs::Vector3dStamped > | gazebo::GzVector3dStampedMsgPtr |
typedef const boost::shared_ptr< const gz_geometry_msgs::WrenchStamped > | gazebo::GzWrenchStampedMsgPtr |