51 std::size_t error = 0;
57 void MoveItSimHWInterface::init()
60 SimHWInterface::init();
66 loadDefaultJointValues();
71 void MoveItSimHWInterface::loadDefaultJointValues()
74 robot_model::RobotModelPtr robot_model = robot_model_loader_->getModel();
77 if (!robot_model->hasJointModelGroup(joint_model_group_))
80 <<
"' for the fake controller manager");
90 robot_state.setToDefaultValues();
93 if (!robot_state.setToDefaultValues(jmg, joint_model_group_pose_))
95 ROS_WARN_STREAM_NAMED(name_,
"Unable to find pose " << joint_model_group_pose_ <<
" for the fake controller "
102 for (std::size_t i = 0; i < joint_names_.size(); ++i)
115 "variable per joint");
120 joint_position_[i] = robot_state.getJointPositions(jm)[0];
121 joint_position_command_[i] = joint_position_[i];
123 if (std::isnan(joint_position_[i]))
126 std::cout << std::endl;
127 std::cout <<
"i: " << i <<
" name: " << jm->
getName() << std::endl;
128 std::cout <<
"joint_model_group: " << jmg->
getName() << std::endl;
130 std::cout <<
"joint_position_[i]: " << joint_position_[i] << std::endl;
131 std::cout <<
"joint_position_command_[i]: " << joint_position_command_[i] << std::endl;
132 robot_state.printStateInfo();