Go to the documentation of this file.
43 #include <boost/shared_ptr.hpp>
44 #include <boost/thread.hpp>
49 #include <std_msgs/Bool.h>
52 #include <gazebo/gazebo.hh>
53 #include <gazebo/physics/physics.hh>
54 #include <gazebo/common/common.hh>
64 class GazeboRosControlPlugin :
public gazebo::ModelPlugin
71 virtual void Load(gazebo::physics::ModelPtr parent, sdf::ElementPtr sdf);
80 std::string
getURDF(std::string param_name)
const;
86 void eStopCB(
const std_msgs::BoolConstPtr& e_stop_active);
110 std::vector<transmission_interface::TransmissionInfo>
transmissions_;
boost::shared_ptr< controller_manager::ControllerManager > controller_manager_
virtual ~GazeboRosControlPlugin()
virtual void Load(gazebo::physics::ModelPtr parent, sdf::ElementPtr sdf)
ros::NodeHandle model_nh_
bool parseTransmissionsFromURDF(const std::string &urdf_string)
ros::Duration control_period_
ros::Time last_write_sim_time_ros_
Plugin template for hardware interfaces for ros_control and Gazebo.
void eStopCB(const std_msgs::BoolConstPtr &e_stop_active)
ros::Time last_update_sim_time_ros_
std::string robot_hw_sim_type_str_
gazebo::physics::ModelPtr parent_model_
void load_robot_hw_sim_srv()
std::string robot_description_
std::string robot_namespace_
std::vector< transmission_interface::TransmissionInfo > transmissions_
boost::shared_ptr< gazebo_ros_control::RobotHWSim > robot_hw_sim_
boost::shared_ptr< pluginlib::ClassLoader< gazebo_ros_control::RobotHWSim > > robot_hw_sim_loader_
boost::thread deferred_load_thread_
ros::Subscriber e_stop_sub_
std::string getURDF(std::string param_name) const
gazebo::event::ConnectionPtr update_connection_
gazebo_ros_control
Author(s): Jonathan Bohren, Dave Coleman
autogenerated on Sun Mar 2 2025 03:49:21