Skip to content

Commit

Permalink
refactored sensor parsing
Browse files Browse the repository at this point in the history
- parse sensor-specific content with a SensorParser (extension point)
- implemented parseCamera() and parseRay() as SensorParsers (visual_sensor_parsers.*)
- added unittest test_sensor_parsing
  • Loading branch information
rhaschke committed Mar 17, 2016
1 parent 0eedac1 commit c43efd8
Show file tree
Hide file tree
Showing 8 changed files with 378 additions and 140 deletions.
11 changes: 8 additions & 3 deletions urdf_parser/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,9 @@ add_library(urdfdom_model SHARED
target_link_libraries(urdfdom_model ${TinyXML_LIBRARIES} ${console_bridge_LIBRARIES} ${Boost_LIBRARIES})
set_target_properties(urdfdom_model PROPERTIES SOVERSION ${URDF_MAJOR_MINOR_VERSION})

add_library(urdfdom_sensor SHARED src/urdf_sensor.cpp)
add_library(urdfdom_sensor SHARED
src/sensor_parser.cpp src/visual_sensor_parsers.cpp
include/urdf_parser/sensor_parser.h include/urdf_parser/visual_sensor_parsers.h)
target_link_libraries(urdfdom_sensor urdfdom_model)
set_target_properties(urdfdom_sensor PROPERTIES SOVERSION ${URDF_MAJOR_MINOR_VERSION})

Expand Down Expand Up @@ -38,16 +40,19 @@ INSTALL(TARGETS check_urdf urdf_to_graphiz urdf_mem_test
DESTINATION ${CMAKE_INSTALL_BINDIR})
INSTALL(TARGETS urdfdom_sensor DESTINATION ${CMAKE_INSTALL_LIBDIR})
INSTALL(TARGETS urdfdom_model_state DESTINATION ${CMAKE_INSTALL_LIBDIR})
INSTALL(FILES include/urdf_parser/exportdecl.h
INSTALL(FILES
include/urdf_parser/exportdecl.h
include/urdf_parser/urdf_parser.h
include/urdf_parser/sensor_parser.h
include/urdf_parser/visual_sensor_parsers.h
include/urdf_parser/link.h
include/urdf_parser/pose.h
DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/urdf_parser)


# unit tests
add_executable(urdf_unit_test test/urdf_unit_test.cpp)
target_link_libraries(urdf_unit_test urdfdom_model ${Boost_LIBRARIES})
target_link_libraries(urdf_unit_test urdfdom_model urdfdom_sensor ${Boost_LIBRARIES})
add_test(NAME urdf_unit_test
WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/test
COMMAND urdf_unit_test)
72 changes: 72 additions & 0 deletions urdf_parser/include/urdf_parser/sensor_parser.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,72 @@
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2008, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the Willow Garage nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/

/* Author: Robert Haschke */

#ifndef URDF_PARSER_URDF_SENSOR_PARSER_H
#define URDF_PARSER_URDF_SENSOR_PARSER_H

#include <string>
#include <map>
#include <tinyxml.h>
#include <urdf_sensor/types.h>

#include "exportdecl.h"

namespace urdf {

URDF_TYPEDEF_CLASS_POINTER(SensorParser);
class URDFDOM_DLLAPI SensorParser {
public:
virtual ~SensorParser() {}
virtual SensorBaseSharedPtr parse(TiXmlElement &sensor_element) = 0;
};

typedef std::map<std::string, SensorSharedPtr> SensorMap;
typedef std::map<std::string, SensorParserSharedPtr> SensorParserMap;

/** parse <sensor> tags in URDF document for which a parser exists in SensorParserMap */
URDFDOM_DLLAPI SensorMap parseSensors(TiXmlDocument &urdf, const SensorParserMap &parsers);

/** convienency function to fetch a sensor with given name and type from the map */
template <typename T>
URDFDOM_DLLAPI boost::shared_ptr<T> getSensor(const std::string &name, SensorMap &sensors) {
SensorMap::iterator s = sensors.find(name);
if (s == sensors.end()) return boost::shared_ptr<T>();
else return boost::dynamic_pointer_cast<T>(s->second->sensor_);
}

}

#endif
Original file line number Diff line number Diff line change
Expand Up @@ -32,15 +32,24 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/

#ifndef URDF_PARSER_SENSOR_H
#define URDF_PARSER_SENSOR_H
/* Author: Robert Haschke */

#include <urdf_sensor/sensor.h>
#include <tinyxml.h>
#ifndef URDF_PARSER_VISUAL_SENSOR_PARSERS_H
#define URDF_PARSER_VISUAL_SENSOR_PARSERS_H

#include "sensor_parser.h"

namespace urdf {

bool parseSensor(Sensor &sensor, TiXmlElement* config);
class URDFDOM_DLLAPI CameraParser : public SensorParser {
public:
SensorBaseSharedPtr parse(TiXmlElement &sensor_element);
};

class URDFDOM_DLLAPI RayParser : public SensorParser {
public:
SensorBaseSharedPtr parse(TiXmlElement &sensor_element);
};

}

Expand Down
2 changes: 1 addition & 1 deletion urdf_parser/src/model.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -261,7 +261,7 @@ TiXmlDocument* exportURDF(const ModelInterface &model)
CONSOLE_BRIDGE_logDebug("urdfdom: exporting link [%s]\n",l->second->name.c_str());
exportLink(*(l->second), robot);
}

for (std::map<std::string, JointSharedPtr>::const_iterator j=model.joints_.begin(); j!=model.joints_.end(); j++)
{
CONSOLE_BRIDGE_logDebug("urdfdom: exporting joint [%s]\n",j->second->name.c_str());
Expand Down
155 changes: 155 additions & 0 deletions urdf_parser/src/sensor_parser.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,155 @@
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2008, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the Willow Garage nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/

/* Author: John Hsu */


#include "urdf_parser/sensor_parser.h"
#include "urdf_parser/pose.h"
#include <urdf_sensor/camera.h>
#include <urdf_sensor/ray.h>

#include <boost/lexical_cast.hpp>
#include <console_bridge/console.h>

namespace urdf {

SensorBaseSharedPtr parseSensorBase(TiXmlElement *sensor_xml, const SensorParserMap &parsers)
{
SensorBaseSharedPtr sensor_;


// find first child element that is not <parent> or <origin>
const char* sensor_type;
TiXmlElement *sensor_base_xml = sensor_xml->FirstChildElement();
while (sensor_base_xml) {
sensor_type = sensor_base_xml->Value();
if (strcmp(sensor_type, "parent") && strcmp(sensor_type, "origin"))
break;
sensor_base_xml = sensor_base_xml->NextSiblingElement();
}

if (sensor_base_xml)
{
SensorParserMap::const_iterator parser = parsers.find(sensor_type);
if (parser != parsers.end() && parser->second)
{
return parser->second->parse(*sensor_base_xml);
}
else
{
CONSOLE_BRIDGE_logDebug("Unknown sensor type %s", sensor_type);
}
}
else
{
CONSOLE_BRIDGE_logError("no child element defining the sensor");
}

return sensor_;
}


bool parseSensor(Sensor &sensor, TiXmlElement* config, const SensorParserMap &parsers)
{
sensor.clear();

const char *name_char = config->Attribute("name");
if (!name_char)
{
CONSOLE_BRIDGE_logError("No name given for the sensor.");
return false;
}
sensor.name_ = std::string(name_char);

// parse parent link name
TiXmlElement *parent_xml = config->FirstChildElement("parent");
const char *parent_link_name_char = parent_xml ? parent_xml->Attribute("link") : NULL;
if (!parent_link_name_char)
{
CONSOLE_BRIDGE_logError("No parent link name given for the sensor.");
return false;
}
sensor.parent_link_ = std::string(parent_link_name_char);

// parse origin
TiXmlElement *o = config->FirstChildElement("origin");
if (o)
{
if (!parsePose(sensor.origin_, o))
return false;
}

// parse sensor
sensor.sensor_ = parseSensorBase(config, parsers);
return true;
}

URDFDOM_DLLAPI
SensorMap parseSensors(TiXmlDocument &urdf_xml, const SensorParserMap &parsers)
{
TiXmlElement *robot_xml = urdf_xml.FirstChildElement("robot");
if (!robot_xml) {
CONSOLE_BRIDGE_logError("Could not find the 'robot' element in the URDF");
}

SensorMap results;
// Get all sensor elements
for (TiXmlElement* sensor_xml = robot_xml->FirstChildElement("sensor");
sensor_xml; sensor_xml = sensor_xml->NextSiblingElement("sensor"))
{
SensorSharedPtr sensor;
sensor.reset(new Sensor);

if (parseSensor(*sensor, sensor_xml, parsers))
{
if (results.find(sensor->name_) != results.end())
{
CONSOLE_BRIDGE_logWarn("Sensor '%s' is not unique. Ignoring consecutive ones.", sensor->name_.c_str());
}
else
{
results.insert(make_pair(sensor->name_, sensor));
CONSOLE_BRIDGE_logDebug("urdfdom: successfully added a new sensor '%s'", sensor->name_.c_str());
}
}
else
{
CONSOLE_BRIDGE_logError("failed to parse sensor element");
}
}
return results;
}

}
Loading

0 comments on commit c43efd8

Please sign in to comment.