36 std::pair<XmlRpc::XmlRpcValue::iterator,bool> res =
_value.asStruct->insert(*it);
58 val = read_typed<T>(wheel[name]);
88 std::string steer_name, drive_name;
89 double max_steer_rate, max_drive_rate;
93 urdf::JointConstSharedPtr steer_joint;
94 if(model && !steer_name.empty()){
95 steer_joint = model->getJoint(steer_name);
104 urdf::JointConstSharedPtr drive_joint;
105 if(model && !drive_name.empty()){
106 drive_joint = model->getJoint(drive_name);
142 urdf::JointConstSharedPtr steer_joint;
143 urdf::Vector3 steer_pos;
146 steer_joint = model->getJoint(geom.
steer_name);
150 steer_pos.x = transform.
getOrigin().getX();
151 steer_pos.y = transform.
getOrigin().getY();
152 steer_pos.z = transform.
getOrigin().getZ();
157 if(!
read_optional(steer_pos.x,
"x_pos", wheel) && !steer_joint){
162 if(!
read_optional(steer_pos.y,
"y_pos", wheel) && !steer_joint){
167 if(!
read_optional(steer_pos.z,
"wheel_radius", merged) && !steer_joint){
172 if(steer_pos.z == 0){
186 urdf::JointConstSharedPtr drive_joint;
188 drive_joint = model->getJoint(geom.
drive_name);
191 const urdf::Vector3& pos = drive_joint->parent_to_joint_origin_transform.position;
192 offset = sqrt(pos.x*pos.x + pos.y * pos.y);
219 for(
size_t i = 0; i < wheel_list.
size(); ++i){
220 new_stuct[boost::lexical_cast<std::string>(i)] = wheel_list[i];
222 wheel_list = new_stuct;
227 return wheel_list.
size() > 0;
234 std::string description_name;
235 bool has_model = read_urdf && nh.
searchParam(
"robot_description", description_name) && model.
initParam(description_name);
241 wheel_params.clear();
244 if (!nh.
getParam(
"wheels", wheel_list)){
259 if(!
parseWheel(params, it->second, merged, has_model?&model:0)){
263 wheel_params.push_back(params);
265 return !wheel_params.empty();
const std::string & getMessage() const
bool parseWheelParams(std::vector< UndercarriageGeom::WheelParams > ¶ms, const ros::NodeHandle &nh, bool read_urdf=true)
double dSteerDriveCoupling
ValueStruct::iterator iterator
bool parsePosCtrlParams(PosCtrlParams ¶ms, XmlRpc::XmlRpcValue &wheel)
bool read(T &val, const std::string &name, XmlRpc::XmlRpcValue &wheel)
T read_typed(XmlRpc::XmlRpcValue &val)
MergedXmlRpcStruct(const XmlRpc::XmlRpcValue &a, const MergedXmlRpcStruct &b, bool recursive=true)
Type const & getType() const
void assertStruct() const
bool parseWheelGeom(WheelGeom &geom, XmlRpc::XmlRpcValue &wheel, MergedXmlRpcStruct &merged, urdf::Model *model)
union XmlRpc::XmlRpcValue::@0 _value
double dMaxDriveRateRadpS
static double from_degrees(double degrees)
bool searchParam(const std::string &key, std::string &result) const
bool parseWheelTransform(const std::string &joint_name, const std::string &parent_link_name, tf2::Transform &transform, urdf::Model *model)
bool parseWheels(std::vector< W > &wheel_params, const ros::NodeHandle &nh, bool read_urdf)
URDF_EXPORT bool initParam(const std::string ¶m)
double dDistSteerAxisToDriveWheelMM
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
bool read_optional(T &val, const std::string &name, XmlRpc::XmlRpcValue &wheel)
MergedXmlRpcStruct(const XmlRpc::XmlRpcValue &a)
bool hasMember(const std::string &name) const
bool parseWheel(W ¶ms, XmlRpc::XmlRpcValue &wheel, MergedXmlRpcStruct &merged, urdf::Model *model)
bool parseCtrlParams(CtrlParams ¶ms, XmlRpc::XmlRpcValue &wheel, urdf::Model *model)
bool getParam(const std::string &key, std::string &s) const
double dMaxSteerRateRadpS
#define ROS_ERROR_STREAM(args)
bool read_with_default(T &val, const std::string &name, XmlRpc::XmlRpcValue &wheel, const T &def)
bool make_wheel_struct(XmlRpc::XmlRpcValue &wheel_list)