51   std::size_t error = 0;
    60   SimHWInterface::init();
    80                           << 
"' for the fake controller manager");
   114                                    "variable per joint");
   125       std::cout << std::endl;
   126       std::cout << 
"i: " << i << 
" name: " << jm->
getName() << std::endl;
   127       std::cout << 
"joint_model_group: " << jmg->
getName() << std::endl;
   129       std::cout << 
"joint_position_[i]: " << 
joint_position_[i] << std::endl;
 
const std::string & getName() const 
std::size_t getVariableCount() const 
std::vector< double > joint_position_command_
std::string joint_model_group_
void loadDefaultJointValues()
#define ROS_ERROR_STREAM_NAMED(name, args)
const std::string & getName() const 
#define ROS_INFO_STREAM_NAMED(name, args)
void init()
Initialize the robot hardware interface. 
void setToDefaultValues()
robot_model_loader::RobotModelLoaderPtr robot_model_loader_
std::vector< std::string > joint_names_
void printStateInfo(std::ostream &out=std::cout) const 
MoveItSimHWInterface(ros::NodeHandle &nh, urdf::Model *urdf_model=NULL)
Constructor. 
const JointModel * getJointModel(const std::string &joint) const 
void shutdownIfError(const std::string &parent_name, std::size_t error_count)
std::vector< double > joint_position_
std::string joint_model_group_pose_
const double * getJointPositions(const std::string &joint_name) const 
bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, bool &value)
static const std::string ROBOT_DESCRIPTION
#define ROS_WARN_STREAM_NAMED(name, args)