Skip to content

Commit 83b7de4

Browse files
committed
added tactile sensors
1 parent 499de2b commit 83b7de4

File tree

5 files changed

+262
-2
lines changed

5 files changed

+262
-2
lines changed

urdf_parser/CMakeLists.txt

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -9,8 +9,9 @@ target_link_libraries(urdfdom_model ${TinyXML_LIBRARIES} ${console_bridge_LIBRAR
99
set_target_properties(urdfdom_model PROPERTIES SOVERSION ${URDF_MAJOR_MINOR_VERSION})
1010

1111
add_library(urdfdom_sensor SHARED
12-
src/sensor_parser.cpp src/visual_sensor_parsers.cpp
13-
include/urdf_parser/sensor_parser.h include/urdf_parser/visual_sensor_parsers.h include/urdf_parser/utils.h)
12+
src/sensor_parser.cpp src/visual_sensor_parsers.cpp src/tactile_sensor_parsers.cpp
13+
include/urdf_parser/sensor_parser.h include/urdf_parser/visual_sensor_parsers.h include/urdf_parser/utils.h
14+
include/urdf_parser/tactile_sensor_parsers.h)
1415
target_link_libraries(urdfdom_sensor urdfdom_model)
1516
set_target_properties(urdfdom_sensor PROPERTIES SOVERSION ${URDF_MAJOR_MINOR_VERSION})
1617

Lines changed: 51 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,51 @@
1+
/*********************************************************************
2+
* Software License Agreement (BSD License)
3+
*
4+
* Copyright (c) 2016, CITEC / Bielefeld University
5+
* All rights reserved.
6+
*
7+
* Redistribution and use in source and binary forms, with or without
8+
* modification, are permitted provided that the following conditions
9+
* are met:
10+
*
11+
* * Redistributions of source code must retain the above copyright
12+
* notice, this list of conditions and the following disclaimer.
13+
* * Redistributions in binary form must reproduce the above
14+
* copyright notice, this list of conditions and the following
15+
* disclaimer in the documentation and/or other materials provided
16+
* with the distribution.
17+
* * Neither the name of the Willow Garage nor the names of its
18+
* contributors may be used to endorse or promote products derived
19+
* from this software without specific prior written permission.
20+
*
21+
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22+
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23+
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24+
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25+
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26+
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27+
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28+
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29+
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30+
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31+
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32+
* POSSIBILITY OF SUCH DAMAGE.
33+
*********************************************************************/
34+
35+
/* Author: Robert Haschke */
36+
37+
#ifndef URDF_PARSER_TACTILE_SENSOR_PARSERS_H
38+
#define URDF_PARSER_TACTILE_SENSOR_PARSERS_H
39+
40+
#include "sensor_parser.h"
41+
42+
namespace urdf {
43+
44+
class URDFDOM_DLLAPI TactileSensorParser : public SensorParser {
45+
public:
46+
SensorBaseSharedPtr parse(TiXmlElement &sensor_element);
47+
};
48+
49+
}
50+
51+
#endif
Lines changed: 168 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,168 @@
1+
/*********************************************************************
2+
* Software License Agreement (BSD License)
3+
*
4+
* Copyright (c) 2016, CITEC / Bielefeld University
5+
* All rights reserved.
6+
*
7+
* Redistribution and use in source and binary forms, with or without
8+
* modification, are permitted provided that the following conditions
9+
* are met:
10+
*
11+
* * Redistributions of source code must retain the above copyright
12+
* notice, this list of conditions and the following disclaimer.
13+
* * Redistributions in binary form must reproduce the above
14+
* copyright notice, this list of conditions and the following
15+
* disclaimer in the documentation and/or other materials provided
16+
* with the distribution.
17+
* * Neither the name of the author nor the names of its
18+
* contributors may be used to endorse or promote products derived
19+
* from this software without specific prior written permission.
20+
*
21+
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22+
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23+
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24+
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25+
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26+
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27+
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28+
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29+
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30+
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31+
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32+
* POSSIBILITY OF SUCH DAMAGE.
33+
*********************************************************************/
34+
35+
/* Author: Robert Haschke */
36+
37+
#include "urdf_parser/tactile_sensor_parsers.h"
38+
#include "urdf_parser/utils.h"
39+
#include "urdf_parser/pose.h"
40+
#include "urdf_parser/link.h"
41+
#include <urdf_sensor/tactile.h>
42+
#include <console_bridge/console.h>
43+
44+
namespace urdf {
45+
46+
/* specialization of parseAttribute(const char* value) for TactileArray::DataOrder */
47+
template <>
48+
TactileArray::DataOrder parseAttribute<TactileArray::DataOrder>(const char* value)
49+
{
50+
if (strcmp(value, "col-major") == 0) return TactileArray::COLUMNMAJOR;
51+
else if (strcmp(value, "row-major") == 0) return TactileArray::ROWMAJOR;
52+
else throw ParseError("invalid order, expecting 'col-major'' or 'row-major'");
53+
}
54+
55+
/* specialization of parseAttribute(const char* value) for Vector2 */
56+
template <>
57+
Vector2<double> parseAttribute<Vector2<double> >(const char* value)
58+
{
59+
std::vector<std::string> pieces;
60+
std::vector<double> xy;
61+
boost::split(pieces, value, boost::is_any_of(" "));
62+
for (unsigned int i = 0; i < pieces.size(); ++i){
63+
if (pieces[i] != ""){
64+
xy.push_back(boost::lexical_cast<double>(pieces[i].c_str()));
65+
}
66+
}
67+
68+
if (xy.size() != 2)
69+
throw ParseError("expecting 2, but found " + boost::lexical_cast<std::string>(xy.size()) + " elements");
70+
71+
return Vector2<double>(xy[0], xy[1]);
72+
}
73+
74+
75+
bool parseTactileTaxel(TactileTaxel &taxel, TiXmlElement *config)
76+
{
77+
taxel.clear();
78+
79+
// taxel frame
80+
if (!parsePose(taxel.origin, config))
81+
return false;
82+
83+
// Geometry
84+
taxel.geometry = parseGeometry(config->FirstChildElement("geometry"));
85+
if (!taxel.geometry)
86+
return false;
87+
88+
// Idx
89+
try {
90+
taxel.idx = parseAttribute<unsigned int>(*config, "idx");
91+
} catch (const ParseError &e) {
92+
CONSOLE_BRIDGE_logError(e.what());
93+
return false;
94+
}
95+
96+
return true;
97+
}
98+
99+
bool parseTactileArray(TactileArray &array, TiXmlElement *config)
100+
{
101+
array.clear();
102+
try {
103+
array.rows = parseAttribute<unsigned int>(*config, "rows");
104+
array.cols = parseAttribute<unsigned int>(*config, "cols");
105+
106+
array.size = parseAttribute<Vector2<double> >(*config, "size");
107+
array.spacing = parseAttribute<Vector2<double> >(*config, "spacing", &array.size);
108+
Vector2<double> origin;
109+
array.offset = parseAttribute<Vector2<double> >(*config, "offset", &origin);
110+
111+
TactileArray::DataOrder order = TactileArray::ROWMAJOR;
112+
array.order = parseAttribute<TactileArray::DataOrder>(*config, "order", &order);
113+
}
114+
catch (const ParseError &e) {
115+
CONSOLE_BRIDGE_logError(e.what());
116+
return false;
117+
}
118+
return true;
119+
}
120+
121+
122+
SensorBaseSharedPtr TactileSensorParser::parse(TiXmlElement &config)
123+
{
124+
TactileSensorSharedPtr tactile(new TactileSensor());
125+
126+
// multiple Taxels (optional)
127+
for (TiXmlElement* taxel_xml = config.FirstChildElement("taxel"); taxel_xml; taxel_xml = taxel_xml->NextSiblingElement("taxel"))
128+
{
129+
TactileTaxelSharedPtr taxel;
130+
taxel.reset(new TactileTaxel());
131+
if (parseTactileTaxel(*taxel, taxel_xml))
132+
{
133+
tactile->taxels_.push_back(taxel);
134+
}
135+
else
136+
{
137+
taxel.reset();
138+
CONSOLE_BRIDGE_logError("Could not parse taxel element for tactile sensor");
139+
return TactileSensorSharedPtr();
140+
}
141+
}
142+
143+
// a single array (optional)
144+
for (TiXmlElement* array_xml = config.FirstChildElement("array"); array_xml; array_xml = array_xml->NextSiblingElement("array"))
145+
{
146+
if (tactile->array_)
147+
{
148+
CONSOLE_BRIDGE_logWarn("Only a single array element is allowed for a tactile sensor");
149+
break; // only warn once
150+
}
151+
tactile->array_.reset(new TactileArray());
152+
if (!parseTactileArray(*tactile->array_, array_xml))
153+
{
154+
tactile->array_.reset();
155+
CONSOLE_BRIDGE_logError("Could not parse array element for tactile sensor");
156+
return TactileSensorSharedPtr();
157+
}
158+
}
159+
160+
if (tactile->array_ && tactile->taxels_.size())
161+
{
162+
CONSOLE_BRIDGE_logWarn("Either an array or multiple taxel elements are allowed for a tactile sensor");
163+
tactile->array_.reset();
164+
}
165+
return tactile;
166+
}
167+
168+
}

urdf_parser/test/basic.urdf

Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -31,4 +31,29 @@
3131
<origin xyz="0 0 0" rpy="0 0 0"/>
3232
<unknown/>
3333
</sensor>
34+
35+
<sensor name="tactile_taxel_sensor" update_rate="100">
36+
<parent link="link1"/>
37+
<origin xyz="0 0 0" rpy="0 0 0"/>
38+
<tactile>
39+
<taxel idx="0" xyz="0 0 0" rpy="0 0 0">
40+
<geometry>
41+
<mesh filename="some.stl" scale="0.001 0.001 0.001"/>
42+
</geometry>
43+
</taxel>
44+
<taxel idx="0" xyz="0 0 0" rpy="0 0 0">
45+
<geometry>
46+
<mesh filename="some.stl" scale="0.001 0.001 0.001"/>
47+
</geometry>
48+
</taxel>
49+
</tactile>
50+
</sensor>
51+
52+
<sensor name="tactile_array_sensor" update_rate="100">
53+
<parent link="link1"/>
54+
<origin xyz="0 0 0" rpy="0 0 0"/>
55+
<tactile>
56+
<array rows="16" cols="16" size="0.1 0.1" spacing="0.1 0.1" offset="0. 0."/>
57+
</tactile>
58+
</sensor>
3459
</robot>

urdf_parser/test/urdf_unit_test.cpp

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,10 @@
11
#include <urdf_parser/urdf_parser.h>
22
#include <urdf_parser/sensor_parser.h>
33
#include <urdf_parser/visual_sensor_parsers.h>
4+
#include <urdf_parser/tactile_sensor_parsers.h>
45
#include <urdf_sensor/camera.h>
56
#include <urdf_sensor/ray.h>
7+
#include <urdf_sensor/tactile.h>
68

79
#include <iostream>
810
#include <fstream>
@@ -185,6 +187,7 @@ BOOST_AUTO_TEST_CASE(test_sensor_parsing)
185187
urdf::SensorParserMap parsers;
186188
parsers.insert(std::make_pair("camera", urdf::SensorParserSharedPtr(new urdf::CameraParser)));
187189
parsers.insert(std::make_pair("ray", urdf::SensorParserSharedPtr(new urdf::RayParser)));
190+
parsers.insert(std::make_pair("tactile", urdf::SensorParserSharedPtr(new urdf::TactileSensorParser)));
188191

189192
urdf::SensorMap sensors = urdf::parseSensors(*xml_doc, parsers);
190193

@@ -214,4 +217,16 @@ BOOST_AUTO_TEST_CASE(test_sensor_parsing)
214217
BOOST_CHECK_EQUAL(ray->vertical_min_angle, 0);
215218
BOOST_CHECK_EQUAL(ray->vertical_max_angle, 0);
216219
}
220+
221+
222+
urdf::TactileSensorSharedPtr tactile = urdf::getSensor<urdf::TactileSensor>("tactile_taxel_sensor", sensors);
223+
BOOST_REQUIRE(tactile);
224+
BOOST_CHECK(tactile->taxels_.size() == 2);
225+
226+
tactile = urdf::getSensor<urdf::TactileSensor>("tactile_array_sensor", sensors);
227+
BOOST_REQUIRE(tactile);
228+
BOOST_CHECK(tactile->array_);
229+
BOOST_CHECK(tactile->array_->order == urdf::TactileArray::ROWMAJOR);
230+
BOOST_CHECK(tactile->array_->spacing.x == tactile->array_->size.x);
231+
BOOST_CHECK(tactile->array_->spacing.y == tactile->array_->size.y);
217232
}

0 commit comments

Comments
 (0)