24 #ifndef GAZEBO_ROS_KATANA_H 25 #define GAZEBO_ROS_KATANA_H 33 #include <gazebo/common/Plugin.hh> 34 #include <gazebo/common/Time.hh> 35 #include <gazebo/common/Events.hh> 36 #include <gazebo/physics/physics.hh> 38 #include <katana_msgs/GripperControllerState.h> 42 #include <boost/thread.hpp> 52 virtual void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf);
control_toolbox::Pid pid_controller_
ros::Publisher controller_state_pub_
katana_gazebo_plugins::IGazeboRosKatanaGripperAction * active_gripper_action_
ros::NodeHandle * rosnode_
virtual void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
void updateActiveGripperAction()
std::vector< std::string > joint_names_
virtual ~GazeboRosKatanaGripper()
common::Time prev_update_time_
virtual void UpdateChild()
event::ConnectionPtr updateConnection
physics::ModelPtr my_parent_
std::vector< katana_gazebo_plugins::IGazeboRosKatanaGripperAction * > gripper_action_list_
physics::WorldPtr my_world_
std::string node_namespace_
static const size_t NUM_JOINTS
physics::JointPtr joints_[NUM_JOINTS]
boost::thread * spinner_thread_
float torque_
Torque applied to the joints.