49   , name_(
"sim_hw_interface")
    53   std::size_t error = 0;
    90   for (std::size_t joint_id = 0; joint_id < 
num_joints_; ++joint_id)
   134   const double delta_pos = std::max(std::min(
p_error_, max_delta_pos), -max_delta_pos);
   135   joint_position_[joint_id] += delta_pos;
   141   if (elapsed_time.
toSec() > 0)
 
std::vector< double > joint_position_command_
#define ROS_INFO_NAMED(name,...)
#define ROS_ERROR_STREAM_NAMED(name, args)
virtual void init()
Initialize the robot hardware interface. 
std::vector< double > joint_position_prev_
void enforceLimits(const ros::Duration &period)
virtual void init()
Initialize the hardware interface. 
std::vector< double > joint_velocity_
std::vector< double > joint_velocity_command_
virtual void read(ros::Duration &elapsed_time)
Read the state from the robot hardware. 
SimHWInterface(ros::NodeHandle &nh, urdf::Model *urdf_model=NULL)
Constructor. 
virtual void enforceLimits(ros::Duration &period)
void shutdownIfError(const std::string &parent_name, std::size_t error_count)
virtual void write(ros::Duration &elapsed_time)
Write the command to the robot hardware. 
std::vector< double > joint_velocity_limits_
std::vector< double > joint_position_
virtual void positionControlSimulation(ros::Duration &elapsed_time, const std::size_t joint_id)
Basic model of system for position control. 
Hardware interface for a robot. 
bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, bool &value)
joint_limits_interface::PositionJointSaturationInterface pos_jnt_sat_interface_
#define ROS_WARN_STREAM_NAMED(name, args)