8 ROS_INFO_STREAM(
"[XBot2Hal constructor]: wait for xbot2core and gazebo to be ready...");
33 std::string path_to_config_file = XBot::Utils::getXBotConfig();
35 _robot = XBot::RobotInterface::getRobot(path_to_config_file);
48 if (! _robot->sense()){
51 _robot->getJointPosition(_jointPositionActualMap);
52 if (_js_msg.name.size() != _jointPositionActualMap.size() ||
53 _js_msg.position.size() != _jointPositionActualMap.size()) {
55 ROS_ERROR_STREAM(
"[XBot2Hal::" << __func__ <<
"] size of _js_msg is different from the size" <<
56 " or what received from the robot (_jointPositionActualMap)");
61 for (
auto it : _jointPositionActualMap ) {
64 _js_msg.name.at(i) = it.first;
65 _js_msg.position.at(i) = it.second;
75 for (
int i=0; i<_mr_msg.position.size(); i++) {
77 _jointPositionReferenceMap[_mr_msg.name.at(i)] = _mr_msg.position.at(i);
80 if (! _robot->setPositionReference(_jointPositionReferenceMap)) {
84 return _robot->move();