Public Member Functions | Private Member Functions | Private Attributes | List of all members
hector_quadrotor_controller_gazebo::QuadrotorHardwareSim Class Reference

#include <quadrotor_hardware_gazebo.h>

Inheritance diagram for hector_quadrotor_controller_gazebo::QuadrotorHardwareSim:
Inheritance graph
[legend]

Public Member Functions

bool enableMotorsCallback (hector_uav_msgs::EnableMotors::Request &req, hector_uav_msgs::EnableMotors::Response &res)
 
virtual bool initSim (const std::string &robot_namespace, ros::NodeHandle model_nh, gazebo::physics::ModelPtr parent_model, const urdf::Model *const urdf_model, std::vector< transmission_interface::TransmissionInfo > transmissions)
 
 QuadrotorHardwareSim ()
 
virtual void readSim (ros::Time time, ros::Duration period)
 
virtual void writeSim (ros::Time time, ros::Duration period)
 
virtual ~QuadrotorHardwareSim ()
 
- Public Member Functions inherited from gazebo_ros_control::RobotHWSim
virtual void eStopActive (const bool active)
 
virtual ~RobotHWSim ()
 
- Public Member Functions inherited from hardware_interface::RobotHW
virtual bool checkForConflict (const std::list< ControllerInfo > &info) const
 
virtual bool checkForConflict (const std::list< ControllerInfo > &info) const
 
virtual void doSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &)
 
virtual void doSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &)
 
virtual bool init (ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh)
 
virtual bool prepareSwitch (const std::list< ControllerInfo > &start_list, const std::list< ControllerInfo > &stop_list)
 
virtual bool prepareSwitch (const std::list< ControllerInfo > &start_list, const std::list< ControllerInfo > &stop_list)
 
virtual void read (const ros::Time &time, const ros::Duration &period)
 
virtual void read (const ros::Time &time, const ros::Duration &period)
 
 RobotHW ()
 
virtual void write (const ros::Time &time, const ros::Duration &period)
 
virtual void write (const ros::Time &time, const ros::Duration &period)
 
virtual ~RobotHW ()
 
- Public Member Functions inherited from hardware_interface::InterfaceManager
T * get ()
 
std::vector< std::string > getInterfaceResources (std::string iface_type) const
 
std::vector< std::string > getNames () const
 
void registerInterface (T *iface)
 
void registerInterfaceManager (InterfaceManager *iface_man)
 

Private Member Functions

bool enableMotors (bool enable)
 

Private Attributes

geometry_msgs::Accel acceleration_
 
std::string base_link_frame_
 
ros::ServiceServer enable_motors_server_
 
gazebo::math::Vector3 gz_acceleration_
 
gazebo::math::Vector3 gz_angular_acceleration_
 
gazebo::math::Vector3 gz_angular_velocity_
 
gazebo::math::Pose gz_pose_
 
gazebo::math::Vector3 gz_velocity_
 
std_msgs::Header header_
 
sensor_msgs::Imu imu_
 
boost::shared_ptr< hector_quadrotor_interface::ImuSubscriberHelperimu_sub_helper_
 
QuadrotorInterface interface_
 
gazebo::physics::LinkPtr link_
 
gazebo::physics::ModelPtr model_
 
ros::Publisher motor_command_publisher_
 
MotorCommandHandlePtr motor_output_
 
hector_uav_msgs::MotorStatus motor_status_
 
boost::shared_ptr< hector_quadrotor_interface::OdomSubscriberHelperodom_sub_helper_
 
gazebo::physics::PhysicsEnginePtr physics_
 
geometry_msgs::Pose pose_
 
geometry_msgs::Twist twist_
 
std::string world_frame_
 
ros::Publisher wrench_command_publisher_
 
hector_quadrotor_interface::WrenchLimiter wrench_limiter_
 
WrenchCommandHandlePtr wrench_output_
 

Additional Inherited Members

- Protected Types inherited from hardware_interface::InterfaceManager
typedef std::vector< InterfaceManager * > InterfaceManagerVector
 
typedef std::map< std::string, void * > InterfaceMap
 
typedef std::map< std::string, std::vector< std::string > > ResourceMap
 
typedef std::map< std::string, size_t > SizeMap
 
- Protected Attributes inherited from hardware_interface::InterfaceManager
boost::ptr_vector< ResourceManagerBaseinterface_destruction_list_
 
InterfaceManagerVector interface_managers_
 
InterfaceMap interfaces_
 
InterfaceMap interfaces_combo_
 
SizeMap num_ifaces_registered_
 
ResourceMap resources_
 

Detailed Description

Definition at line 49 of file quadrotor_hardware_gazebo.h.

Constructor & Destructor Documentation

hector_quadrotor_controller_gazebo::QuadrotorHardwareSim::QuadrotorHardwareSim ( )

Definition at line 36 of file quadrotor_hardware_gazebo.cpp.

hector_quadrotor_controller_gazebo::QuadrotorHardwareSim::~QuadrotorHardwareSim ( )
virtual

Definition at line 49 of file quadrotor_hardware_gazebo.cpp.

Member Function Documentation

bool hector_quadrotor_controller_gazebo::QuadrotorHardwareSim::enableMotors ( bool  enable)
private

Definition at line 280 of file quadrotor_hardware_gazebo.cpp.

bool hector_quadrotor_controller_gazebo::QuadrotorHardwareSim::enableMotorsCallback ( hector_uav_msgs::EnableMotors::Request &  req,
hector_uav_msgs::EnableMotors::Response &  res 
)

Definition at line 274 of file quadrotor_hardware_gazebo.cpp.

bool hector_quadrotor_controller_gazebo::QuadrotorHardwareSim::initSim ( const std::string &  robot_namespace,
ros::NodeHandle  model_nh,
gazebo::physics::ModelPtr  parent_model,
const urdf::Model *const  urdf_model,
std::vector< transmission_interface::TransmissionInfo transmissions 
)
virtual

Implements gazebo_ros_control::RobotHWSim.

Definition at line 54 of file quadrotor_hardware_gazebo.cpp.

void hector_quadrotor_controller_gazebo::QuadrotorHardwareSim::readSim ( ros::Time  time,
ros::Duration  period 
)
virtual

Implements gazebo_ros_control::RobotHWSim.

Definition at line 118 of file quadrotor_hardware_gazebo.cpp.

void hector_quadrotor_controller_gazebo::QuadrotorHardwareSim::writeSim ( ros::Time  time,
ros::Duration  period 
)
virtual

Implements gazebo_ros_control::RobotHWSim.

Definition at line 233 of file quadrotor_hardware_gazebo.cpp.

Member Data Documentation

geometry_msgs::Accel hector_quadrotor_controller_gazebo::QuadrotorHardwareSim::acceleration_
private

Definition at line 74 of file quadrotor_hardware_gazebo.h.

std::string hector_quadrotor_controller_gazebo::QuadrotorHardwareSim::base_link_frame_
private

Definition at line 84 of file quadrotor_hardware_gazebo.h.

ros::ServiceServer hector_quadrotor_controller_gazebo::QuadrotorHardwareSim::enable_motors_server_
private

Definition at line 103 of file quadrotor_hardware_gazebo.h.

gazebo::math::Vector3 hector_quadrotor_controller_gazebo::QuadrotorHardwareSim::gz_acceleration_
private

Definition at line 95 of file quadrotor_hardware_gazebo.h.

gazebo::math::Vector3 hector_quadrotor_controller_gazebo::QuadrotorHardwareSim::gz_angular_acceleration_
private

Definition at line 95 of file quadrotor_hardware_gazebo.h.

gazebo::math::Vector3 hector_quadrotor_controller_gazebo::QuadrotorHardwareSim::gz_angular_velocity_
private

Definition at line 95 of file quadrotor_hardware_gazebo.h.

gazebo::math::Pose hector_quadrotor_controller_gazebo::QuadrotorHardwareSim::gz_pose_
private

Definition at line 94 of file quadrotor_hardware_gazebo.h.

gazebo::math::Vector3 hector_quadrotor_controller_gazebo::QuadrotorHardwareSim::gz_velocity_
private

Definition at line 95 of file quadrotor_hardware_gazebo.h.

std_msgs::Header hector_quadrotor_controller_gazebo::QuadrotorHardwareSim::header_
private

Definition at line 71 of file quadrotor_hardware_gazebo.h.

sensor_msgs::Imu hector_quadrotor_controller_gazebo::QuadrotorHardwareSim::imu_
private

Definition at line 75 of file quadrotor_hardware_gazebo.h.

boost::shared_ptr<hector_quadrotor_interface::ImuSubscriberHelper> hector_quadrotor_controller_gazebo::QuadrotorHardwareSim::imu_sub_helper_
private

Definition at line 98 of file quadrotor_hardware_gazebo.h.

QuadrotorInterface hector_quadrotor_controller_gazebo::QuadrotorHardwareSim::interface_
private

Definition at line 78 of file quadrotor_hardware_gazebo.h.

gazebo::physics::LinkPtr hector_quadrotor_controller_gazebo::QuadrotorHardwareSim::link_
private

Definition at line 87 of file quadrotor_hardware_gazebo.h.

gazebo::physics::ModelPtr hector_quadrotor_controller_gazebo::QuadrotorHardwareSim::model_
private

Definition at line 86 of file quadrotor_hardware_gazebo.h.

ros::Publisher hector_quadrotor_controller_gazebo::QuadrotorHardwareSim::motor_command_publisher_
private

Definition at line 102 of file quadrotor_hardware_gazebo.h.

MotorCommandHandlePtr hector_quadrotor_controller_gazebo::QuadrotorHardwareSim::motor_output_
private

Definition at line 81 of file quadrotor_hardware_gazebo.h.

hector_uav_msgs::MotorStatus hector_quadrotor_controller_gazebo::QuadrotorHardwareSim::motor_status_
private

Definition at line 76 of file quadrotor_hardware_gazebo.h.

boost::shared_ptr<hector_quadrotor_interface::OdomSubscriberHelper> hector_quadrotor_controller_gazebo::QuadrotorHardwareSim::odom_sub_helper_
private

Definition at line 99 of file quadrotor_hardware_gazebo.h.

gazebo::physics::PhysicsEnginePtr hector_quadrotor_controller_gazebo::QuadrotorHardwareSim::physics_
private

Definition at line 88 of file quadrotor_hardware_gazebo.h.

geometry_msgs::Pose hector_quadrotor_controller_gazebo::QuadrotorHardwareSim::pose_
private

Definition at line 72 of file quadrotor_hardware_gazebo.h.

geometry_msgs::Twist hector_quadrotor_controller_gazebo::QuadrotorHardwareSim::twist_
private

Definition at line 73 of file quadrotor_hardware_gazebo.h.

std::string hector_quadrotor_controller_gazebo::QuadrotorHardwareSim::world_frame_
private

Definition at line 84 of file quadrotor_hardware_gazebo.h.

ros::Publisher hector_quadrotor_controller_gazebo::QuadrotorHardwareSim::wrench_command_publisher_
private

Definition at line 101 of file quadrotor_hardware_gazebo.h.

hector_quadrotor_interface::WrenchLimiter hector_quadrotor_controller_gazebo::QuadrotorHardwareSim::wrench_limiter_
private

Definition at line 83 of file quadrotor_hardware_gazebo.h.

WrenchCommandHandlePtr hector_quadrotor_controller_gazebo::QuadrotorHardwareSim::wrench_output_
private

Definition at line 80 of file quadrotor_hardware_gazebo.h.


The documentation for this class was generated from the following files:


hector_quadrotor_controller_gazebo
Author(s): Johannes Meyer
autogenerated on Mon Jun 10 2019 13:36:51