From 5bf1755e80a41638254efaa3f219fd1dbb525ccc Mon Sep 17 00:00:00 2001 From: Silvio Traversaro Date: Tue, 2 Apr 2024 18:28:36 +0200 Subject: [PATCH 1/2] Add support for loading vector with parenthesis As discussed in https://github.com/robotology/yarp/discussions/3092, it is recomendded for future software that uses YARP to use vectors in configuration file by indicating them with parenthesis. gazebo-yarp-plugins used to load the vectors from configuration files expecting no parenthesis. After this commit, now plugins support both the with parentheis and without parenthesis style, printing a warning if the without parenthesis style is used. If you can require gazebo-yarp-plugins 4.11.0, consider switching your configuration files to the vector with parenthesis style. --- .../common/include/GazeboYarpPlugins/common.h | 88 ++++- .../controlboard/src/ControlBoardDriver.cpp | 354 +++++++++--------- .../src/FakeControlBoardDriver.cpp | 10 +- plugins/maissensor/src/MaisSensorDriver.cpp | 12 +- 4 files changed, 270 insertions(+), 194 deletions(-) diff --git a/libraries/common/include/GazeboYarpPlugins/common.h b/libraries/common/include/GazeboYarpPlugins/common.h index 0997b24bc..8add15ee8 100644 --- a/libraries/common/include/GazeboYarpPlugins/common.h +++ b/libraries/common/include/GazeboYarpPlugins/common.h @@ -9,6 +9,11 @@ #include #include +#include + +#include +#include +#include namespace GazeboYarpPlugins { @@ -70,8 +75,89 @@ namespace GazeboYarpPlugins { if (pos == std::string::npos) { return fullString; } else { - return fullString.substr(pos + separator.size() - 1); + return fullString.substr(pos + separator.size() - 1); + } + } + + template + inline T readElementFromValue(yarp::os::Value& val); + + template<> + inline double readElementFromValue(yarp::os::Value& val) + { + return val.asFloat64(); + } + + template<> + inline std::string readElementFromValue(yarp::os::Value& val) + { + return val.asString(); + } + + /** + * Get a vector from a parameter, using both the recommended style: + * nameOfList (elem1 elem2 elem3) + * or the deprecated (since YARP 3.10): + * nameOfList elem1 elem2 elem3 + * + * + * \brief Get vector from YARP configuration + * \return true if the parsing was successful, false otherwise + */ + template + inline bool readVectorFromConfigFile(const yarp::os::Searchable& params, const std::string&listName, std::vector& outputList) + { + bool vectorPopulated = false; + outputList.resize(0); + yarp::os::Value& val = params.find(listName); + if (!val.isNull() && val.isList()) + { + yarp::os::Bottle* listBot = val.asList(); + outputList.resize(listBot->size()); + + for (size_t i=0; i < outputList.size(); i++) + { + outputList[i] = readElementFromValue(listBot->get(i)); + } + + vectorPopulated = true; + } + else + { + // Try to interpreter the list via findGroup + yarp::os::Bottle listBottleAndKey = params.findGroup(listName); + if (!listBottleAndKey.isNull()) + { + yWarning() << "Parameter " << listName << " should be a list, but its format is deprecated as parenthesis are missing." + << " Please add parentesis to the list, as documented in https://github.com/robotology/yarp/discussions/3092 ."; + + outputList.resize(listBottleAndKey.size()-1); + + for (size_t i=0; i < outputList.size(); i++) + { + outputList[i] = readElementFromValue(listBottleAndKey.get(i+1)); + } + vectorPopulated = true; + } + } + return vectorPopulated; + } + + /** + * Convert a vector to a string for printing. + */ + template + inline std::string vectorToString(std::vector& outputList) + { + std::stringstream ss; + for (size_t i = 0; i < outputList.size(); ++i) { + ss << outputList[i]; + if (i != outputList.size() - 1) + { + ss << " "; + } } + return ss.str(); } } diff --git a/plugins/controlboard/src/ControlBoardDriver.cpp b/plugins/controlboard/src/ControlBoardDriver.cpp index 96685ae05..09227c1cb 100644 --- a/plugins/controlboard/src/ControlBoardDriver.cpp +++ b/plugins/controlboard/src/ControlBoardDriver.cpp @@ -25,26 +25,45 @@ GazeboYarpControlBoardDriver::GazeboYarpControlBoardDriver() : m_deviceName(""), GazeboYarpControlBoardDriver::~GazeboYarpControlBoardDriver() {} - -//generic function that check is key1 is present in input bottle and that the result has size elements +// generic function that check is key1 is present in input bottle and that the result has size elements // return true/false -bool validate(Bottle &input, Bottle &out, const std::string &key1, const std::string &txt, int size) +bool getVectorFromConf(Bottle &input, std::vector &out, const std::string &key1, const std::string &txt, int expectedSize) { - Bottle &tmp=input.findGroup(key1.c_str(), txt.c_str()); - if (tmp.isNull()) + bool vecOk = GazeboYarpPlugins::readVectorFromConfigFile(input, key1, out); + + if (!vecOk) { yCError(GAZEBOCONTROLBOARD) << key1.c_str() << "not found"; return false; } - if(tmp.size()!=size) + if(out.size()!=expectedSize) { yCError(GAZEBOCONTROLBOARD) << key1.c_str() << "incorrect number of entries"; return false; } - out=tmp; return true; } +bool getVectorFromConf(Bottle &input, yarp::sig::Vector&out, const std::string &key1, const std::string &txt, int expectedSize) +{ + std::vector tempVec; + bool vecOk = GazeboYarpPlugins::readVectorFromConfigFile(input, key1, tempVec); + + if (!vecOk) + { + return false; + } + + out.resize(tempVec.size()); + for (size_t i=0; i < tempVec.size(); i++) + { + out[i] = tempVec[i]; + } + + return true; +} + + bool GazeboYarpControlBoardDriver::gazebo_init() { //m_robot = gazebo_pointer_wrapper::getModel(); @@ -133,10 +152,10 @@ bool GazeboYarpControlBoardDriver::gazebo_init() yarp::os::Bottle& traj_bottle = m_pluginParameters.findGroup("TRAJECTORY_GENERATION"); if (!traj_bottle.isNull()) { - yarp::os::Bottle& traj_type = traj_bottle.findGroup("trajectory_type"); - if (!traj_type.isNull()) + yarp::os::Value trajTypeVal = traj_bottle.find("trajectory_type"); + if (!trajTypeVal.isNull() && trajTypeVal.isString()) { - std::string traj_type_s = traj_type.get(1).asString(); + std::string traj_type_s = trajTypeVal.asString(); if (traj_type_s == "constant_speed") {for (size_t i = 0; i < m_numberOfJoints; ++i) {trajectory_generator_type[i] = yarp::dev::TRAJECTORY_TYPE_CONST_SPEED;}} else if (traj_type_s == "trapezoidal_speed") {for (size_t i = 0; i < m_numberOfJoints; ++i) {trajectory_generator_type[i] = yarp::dev::TRAJECTORY_TYPE_TRAP_SPEED;}} else if (traj_type_s == "minimum_jerk") {/* default */} @@ -368,12 +387,13 @@ bool GazeboYarpControlBoardDriver::gazebo_init() m_actuatedAxesPosLimits.resize(nrOfActuatedAxes); // TODO this should be done in a better way m_actuatedAxesVelLimits = m_jointVelLimits; - yarp::os::Bottle& actuated_axis_pos_limit_min = coupling_group_bottle.findGroup("actuatedAxesPosMin"); - if (!actuated_axis_pos_limit_min.isNull() && static_cast(actuated_axis_pos_limit_min.size()) == nrOfActuatedAxes+1) + std::vector actuated_axis_pos_limit_min; + bool vecOk = getVectorFromConf(coupling_group_bottle, actuated_axis_pos_limit_min, "actuatedAxesPosMin", "Actuated axes max position", nrOfActuatedAxes); + if (vecOk) { for(size_t i = 0; i < m_actuatedAxesPosLimits.size(); ++i) { - m_actuatedAxesPosLimits[i].min = actuated_axis_pos_limit_min.get(i+1).asFloat64(); + m_actuatedAxesPosLimits[i].min = actuated_axis_pos_limit_min[i]; } } else @@ -381,12 +401,14 @@ bool GazeboYarpControlBoardDriver::gazebo_init() yCError(GAZEBOCONTROLBOARD) << "Failed to get actuated axes min limits"; return false; } - yarp::os::Bottle& actuated_axis_pos_limit_max = coupling_group_bottle.findGroup("actuatedAxesPosMax"); - if (!actuated_axis_pos_limit_max.isNull() && static_cast(actuated_axis_pos_limit_max.size()) == nrOfActuatedAxes+1) + + std::vector actuated_axis_pos_limit_max; + vecOk = getVectorFromConf(coupling_group_bottle, actuated_axis_pos_limit_min, "actuatedAxesPosMax", "Actuated axes max position", nrOfActuatedAxes); + if (!vecOk) { for(size_t i = 0; i < m_actuatedAxesPosLimits.size(); ++i) { - m_actuatedAxesPosLimits[i].max = actuated_axis_pos_limit_max.get(i+1).asFloat64(); + m_actuatedAxesPosLimits[i].max = actuated_axis_pos_limit_max[i]; } } else @@ -822,12 +844,14 @@ bool GazeboYarpControlBoardDriver::setMinMaxPos() yarp::os::Bottle& limits_bottle = m_pluginParameters.findGroup("LIMITS"); if (!limits_bottle.isNull()) { - yarp::os::Bottle& pos_limit_max = limits_bottle.findGroup("jntPosMax"); - if (!pos_limit_max.isNull() && static_cast(pos_limit_max.size()) == m_numberOfJoints+1) + std::vector pos_limit_max; + bool vecOk = getVectorFromConf(limits_bottle, pos_limit_max, "jntPosMax", "Joint max position", m_numberOfJoints); + + if (vecOk) { for(size_t i = 0; i < m_numberOfJoints; ++i) { - m_jointPosLimits[i].max = pos_limit_max.get(i+1).asFloat64(); + m_jointPosLimits[i].max = pos_limit_max[i]; } } @@ -836,12 +860,15 @@ bool GazeboYarpControlBoardDriver::setMinMaxPos() yCError(GAZEBOCONTROLBOARD) << "Failed to parse jntPosMax parameter"; return false; } - yarp::os::Bottle& pos_limit_min = limits_bottle.findGroup("jntPosMin"); - if (!pos_limit_min.isNull() && static_cast(pos_limit_min.size()) == m_numberOfJoints+1) + + std::vector pos_limit_min; + vecOk = getVectorFromConf(limits_bottle, pos_limit_min, "jntPosMin", "Joint min position", m_numberOfJoints); + + if (vecOk) { for(size_t i = 0; i < m_numberOfJoints; ++i) { - m_jointPosLimits[i].min = pos_limit_min.get(i+1).asFloat64(); + m_jointPosLimits[i].min = pos_limit_min[i]; } } else @@ -871,12 +898,15 @@ bool GazeboYarpControlBoardDriver::setMinMaxVel() yarp::os::Bottle& limits_bottle = m_pluginParameters.findGroup("LIMITS"); if (!limits_bottle.isNull()) { - yarp::os::Bottle& vel_limits = limits_bottle.findGroup("jntVelMax"); - if (!vel_limits.isNull()) + + std::vector vel_limit_max; + bool vecOk = getVectorFromConf(limits_bottle, vel_limit_max, "jntVelMax", "Joint max velocity", m_numberOfJoints); + + if (vecOk) { for(size_t i = 0; i < m_numberOfJoints; ++i) { - m_jointVelLimits[i].max = vel_limits.get(i+1).asFloat64(); + m_jointVelLimits[i].max = vel_limit_max[i]; m_jointVelLimits[i].min = 0; } } @@ -915,39 +945,25 @@ bool GazeboYarpControlBoardDriver::setTrajectoryReferences() if (!traj_bottle.isNull()) { - yarp::os::Bottle& refSpeeds = traj_bottle.findGroup("refSpeed"); + std::vector refSpeeds; + bool vecOk = getVectorFromConf(traj_bottle, refSpeeds, "refSpeed", "Reference speed", m_numberOfJoints); - if (!refSpeeds.isNull()) + if (vecOk) { - if (static_cast(refSpeeds.size()) - 1 == m_numberOfJoints) - { - for (size_t j = 0; j < m_numberOfJoints; ++j) - { - m_trajectoryGenerationReferenceSpeed[j] = refSpeeds.get(j + 1).asFloat64(); - } - } - else + for (size_t j = 0; j < m_numberOfJoints; ++j) { - yCError(GAZEBOCONTROLBOARD) << "Invalid number of refSpeed params"; - return false; + m_trajectoryGenerationReferenceSpeed[j] = refSpeeds[j]; } } - yarp::os::Bottle& refAccelerations = traj_bottle.findGroup("refAcceleration"); + std::vector refAccelerations; + vecOk = getVectorFromConf(traj_bottle, refAccelerations, "refAcceleration", "Reference acceleration", m_numberOfJoints); - if (!refAccelerations.isNull()) + if (vecOk) { - if (static_cast(refAccelerations.size()) - 1 == m_numberOfJoints) + for (size_t j = 0; j < m_numberOfJoints; ++j) { - for (size_t j = 0; j < m_numberOfJoints; ++j) - { - m_trajectoryGenerationReferenceAcceleration[j] = refAccelerations.get(j + 1).asFloat64(); - } - } - else - { - yCError(GAZEBOCONTROLBOARD) << "Invalid number of refAcceleration params"; - return false; + m_trajectoryGenerationReferenceAcceleration[j] = refAccelerations[j]; } } } @@ -961,32 +977,29 @@ bool GazeboYarpControlBoardDriver::setTrajectoryReferences() } } - yCDebug(GAZEBOCONTROLBOARD) << "refSpeed: [ " << m_trajectoryGenerationReferenceSpeed.toString() << " ] "; - yCDebug(GAZEBOCONTROLBOARD) << "refAcceleration: [ " << m_trajectoryGenerationReferenceAcceleration.toString() << " ] "; - return true; } + + bool GazeboYarpControlBoardDriver::setJointNames() //WORKS { - yarp::os::Bottle joint_names_bottle = m_pluginParameters.findGroup("jointNames"); + bool paramOk = GazeboYarpPlugins::readVectorFromConfigFile(m_pluginParameters, "jointNames", controlboard_joint_names); - if (joint_names_bottle.isNull()) { - yCError(GAZEBOCONTROLBOARD) << "GazeboYarpControlBoardDriver::setJointNames(): Error cannot find jointNames." ; + if (!paramOk) { + yCError(GAZEBOCONTROLBOARD) << "GazeboYarpControlBoardDriver::setJointNames(): Error cannot find jointNames parameter." ; return false; } - int nr_of_joints = joint_names_bottle.size()-1; + int nr_of_joints = controlboard_joint_names.size(); m_jointNames.resize(nr_of_joints); m_jointPointers.resize(nr_of_joints); const gazebo::physics::Joint_V & gazebo_models_joints = m_robot->GetJoints(); - controlboard_joint_names.clear(); for (size_t i = 0; i < m_jointNames.size(); i++) { bool joint_found = false; - controlboard_joint_names.push_back(joint_names_bottle.get(i+1).asString().c_str()); for (size_t gazebo_joint = 0; gazebo_joint < gazebo_models_joints.size() && !joint_found; gazebo_joint++) { std::string gazebo_joint_name = gazebo_models_joints[gazebo_joint]->GetName(); @@ -1001,7 +1014,7 @@ bool GazeboYarpControlBoardDriver::setJointNames() //WORKS if (!joint_found) { yCError(GAZEBOCONTROLBOARD) << "GazeboYarpControlBoardDriver::setJointNames(): cannot find joint '" << controlboard_joint_names[i] << "' (" << i+1 << " of " << nr_of_joints << ") " << "\n"; - yCError(GAZEBOCONTROLBOARD) << "jointNames are " << joint_names_bottle.toString() << "\n"; + yCError(GAZEBOCONTROLBOARD) << "jointNames are " << GazeboYarpPlugins::vectorToString(controlboard_joint_names) << "\n"; m_jointNames.resize(0); m_jointPointers.resize(0); return false; @@ -1058,16 +1071,15 @@ bool GazeboYarpControlBoardDriver::setPIDsForGroup_POSITION(std::vector tempVec; + if (!getVectorFromConf(pidGroup, tempVec, "kp", "Pid kp parameter", m_numberOfJoints)) { error = true; } else { for (j=0; j tempVec; + if (!getVectorFromConf(pidGroup, tempVec, "kp", "Pid kp parameter", m_numberOfJoints)) {error=true;} else {for (j=0; j tempVec; + if (!getVectorFromConf(pidGroup, tempVec, "stiffness", "stiffness", m_numberOfJoints)) {error=true;} else {for (j=0; j(positionToleranceLinear_bot.size()) != 2) { - yCError(GAZEBOCONTROLBOARD)<<"Invalid number of params:positionToleranceLinear:"<(positionToleranceLinear_bot.size()); - return false; - } - - yarp::os::Value tmp=positionToleranceLinear_bot.get(1); - if (!tmp.isFloat64()) + yarp::os::Value positionToleranceLinear_val = kin_chain_bot.find("positionToleranceLinear"); + if (positionToleranceLinear_val.isNull() || !positionToleranceLinear_val.isFloat64()) { yCError(GAZEBOCONTROLBOARD)<<"Invalid param type:positionToleranceLinear"; return false; } - m_robotPositionToleranceLinear=tmp.asFloat64(); - - yCDebug(GAZEBOCONTROLBOARD)<<"positionToleranceLinear: [ "<(positionToleranceRevolute_bot.size()) != 2) { - yCError(GAZEBOCONTROLBOARD)<<"Invalid number of params:positionToleranceRevolute:"<(positionToleranceRevolute_bot.size()); - return false; - } - - yarp::os::Value tmp=positionToleranceRevolute_bot.get(1); - if (!tmp.isFloat64()) + yarp::os::Value positionToleranceRevolute_val = kin_chain_bot.find("positionToleranceRevolute"); + if (positionToleranceRevolute_val.isNull() || !positionToleranceRevolute_val.isFloat64()) { yCError(GAZEBOCONTROLBOARD)<<"Invalid param type:positionToleranceRevolute"; return false; } - m_robotPositionToleranceRevolute=tmp.asFloat64(); + m_robotPositionToleranceLinear=positionToleranceRevolute_val.asFloat64(); - yCDebug(GAZEBOCONTROLBOARD)<<"positionToleranceRevolute: [ "<(max_torque_bot.size()) - 1 == m_numberOfJoints) { - for(size_t i = 0; i < m_numberOfJoints; ++i) - m_maxTorques[i] = max_torque_bot.get(i+1).asFloat64(); - } else - yCError(GAZEBOCONTROLBOARD)<<"Invalid number of params"; - } else - yCWarning(GAZEBOCONTROLBOARD)<<"No max torques value found in ini file, default one will be used!"; - yCDebug(GAZEBOCONTROLBOARD)<<"max_torques: [ "<(min_stiff_bot.size()) - 1 == m_numberOfJoints) { - for(size_t i = 0; i < m_numberOfJoints; ++i) - m_minStiffness[i] = min_stiff_bot.get(i+1).asFloat64(); - } else - yCError(GAZEBOCONTROLBOARD)<<"Invalid number of params"; - } else + bool vecOk = getVectorFromConf(kin_chain_bot, m_minStiffness, "min_stiffness", "Minimum value of stiffness", m_numberOfJoints); + + if (!vecOk) + { + yCError(GAZEBOCONTROLBOARD)<< "Impossible to parse min_stiffness param"; + } + } else { yCWarning(GAZEBOCONTROLBOARD)<<"No minimum stiffness value found in ini file, default one will be used!"; + } if (kin_chain_bot.check("max_stiffness")) { - yCInfo(GAZEBOCONTROLBOARD)<<"max_stiffness param found!"; - yarp::os::Bottle& max_stiff_bot = kin_chain_bot.findGroup("max_stiffness"); - if (static_cast(max_stiff_bot.size())-1 == m_numberOfJoints) { - for (size_t i = 0; i < m_numberOfJoints; ++i) - m_maxStiffness[i] = max_stiff_bot.get(i+1).asFloat64(); - } else - yCError(GAZEBOCONTROLBOARD)<<"Invalid number of params"; + bool vecOk = getVectorFromConf(kin_chain_bot, m_maxStiffness, "max_stiffness", "Maximum value of stiffness", m_numberOfJoints); + + if (!vecOk) + { + yCError(GAZEBOCONTROLBOARD)<< "Impossible to parse max_stiffness param"; + } } - else + else { yCWarning(GAZEBOCONTROLBOARD)<<"No maximum stiffness value found in ini file, default one will be used!"; + } if (kin_chain_bot.check("min_damping")) { - yCInfo(GAZEBOCONTROLBOARD)<<"min_damping param found!"; - yarp::os::Bottle& min_damping_bot = kin_chain_bot.findGroup("min_damping"); - if(static_cast(min_damping_bot.size())-1 == m_numberOfJoints) { - for(size_t i = 0; i < m_numberOfJoints; ++i) - m_minDamping[i] = min_damping_bot.get(i+1).asFloat64(); - } else - yCError(GAZEBOCONTROLBOARD)<<"Invalid number of params"; - } else + bool vecOk = getVectorFromConf(kin_chain_bot, m_minDamping, "min_damping", "Minimum value of damping", m_numberOfJoints); + + if (!vecOk) + { + yCError(GAZEBOCONTROLBOARD)<< "Impossible to parse min_damping param"; + } + } else { yCWarning(GAZEBOCONTROLBOARD)<<"No minimum dampings value found in ini file, default one will be used!"; + } if(kin_chain_bot.check("max_damping")) { - yCInfo(GAZEBOCONTROLBOARD)<<"max_damping param found!"; - yarp::os::Bottle& max_damping_bot = kin_chain_bot.findGroup("max_damping"); - if (static_cast(max_damping_bot.size()) - 1 == m_numberOfJoints) { - for(size_t i = 0; i < m_numberOfJoints; ++i) - m_maxDamping[i] = max_damping_bot.get(i+1).asFloat64(); - } else - yCError(GAZEBOCONTROLBOARD)<<"Invalid number of params"; - } else + bool vecOk = getVectorFromConf(kin_chain_bot, m_maxDamping, "max_damping", "Maximum value of damping", m_numberOfJoints); + + if (!vecOk) + { + yCError(GAZEBOCONTROLBOARD)<< "Impossible to parse max_damping param"; + } + } else { yCWarning(GAZEBOCONTROLBOARD)<<"No maximum damping value found in ini file, default one will be used!"; + } - yCDebug(GAZEBOCONTROLBOARD)<<"min_stiffness: [ "< tempVec; + if (!getVectorFromConf(simGroup, tempVec, "kPWM", "kPWM parameter", m_numberOfJoints)) { yCError(GAZEBOCONTROLBOARD) << "Missing kPWM parameter"; return false; } else { for (size_t j=0; j Date: Tue, 2 Apr 2024 18:31:33 +0200 Subject: [PATCH 2/2] single_pendulum: Remove deprecated constructs from configuration files --- .../conf/gazebo_controlboard.ini | 36 +++++++++++++------ tutorial/model/single_pendulum/model.urdf | 2 +- 2 files changed, 27 insertions(+), 11 deletions(-) diff --git a/tutorial/model/single_pendulum/conf/gazebo_controlboard.ini b/tutorial/model/single_pendulum/conf/gazebo_controlboard.ini index 891220da3..74c93cb15 100644 --- a/tutorial/model/single_pendulum/conf/gazebo_controlboard.ini +++ b/tutorial/model/single_pendulum/conf/gazebo_controlboard.ini @@ -1,14 +1,30 @@ disableImplicitNetworkWrapper yarpDeviceName controlboard_plugin_device -jointNames joint +jointNames (joint) -#PIDs: -# this information is used to set the PID values in simulation for GAZEBO, we need only the first three values -[GAZEBO_PIDS] -#Torso -Pid0 1000.0 2.0 0.1 9999 9999 9 9 - -[GAZEBO_VELOCITY_PIDS] -#Torso -Pid0 500.0 2.0 0.1 9999 9999 9 9 +[POSITION_CONTROL] +controlUnits metric_units +controlLaw joint_pid_gazebo_v1 +kp (1000.0) +kd (2.0) +ki (0.1) +maxInt (9999) +maxOutput (9999) +shift (0.0) +ko (0.0) +stictionUp (0.0) +stictionDwn (0.0) +[VELOCITY_CONTROL] +controlUnits metric_units +controlLaw joint_pid_gazebo_v1 +velocityControlImplementationType integrator_and_position_pid +kp (500.0) +kd (2.0) +ki (0.1) +maxInt (9999) +maxOutput (9999) +shift (0.0) +ko (0.0) +stictionUp (0.0) +stictionDwn (0.0) diff --git a/tutorial/model/single_pendulum/model.urdf b/tutorial/model/single_pendulum/model.urdf index 02307fb9b..2c6189f6a 100644 --- a/tutorial/model/single_pendulum/model.urdf +++ b/tutorial/model/single_pendulum/model.urdf @@ -65,7 +65,7 @@ model://single_pendulum/conf/gazebo_controlboard.ini - 0.0 0.0 + 0.0