mocap_config.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2018, Houston Mechatronics Inc., JD Yamokoski
3  * Copyright (c) 2012, Clearpath Robotics, Inc., Alex Bencz
4  * All rights reserved.
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright notice,
10  * this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in the
13  * documentation and/or other materials provided with the distribution.
14  * 3. Neither the name of the copyright holder nor the names of its
15  * contributors may be used to endorse or promote products derived from
16  * this software without specific prior written permission.
17  *
18  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
22  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28  * POSSIBILITY OF SUCH DAMAGE.
29  */
31 
32 #include <string>
33 #include <XmlRpcValue.h>
34 
35 namespace mocap_optitrack
36 {
37 
38 namespace impl
39 {
40 template<typename T>
42  XmlRpc::XmlRpcValue& config_node,
43  std::string const& key,
44  T& value)
45 {
46  return false;
47 }
48 
49 template<>
50 bool check_and_get_param<std::string>(
51  XmlRpc::XmlRpcValue& config_node,
52  std::string const& key,
53  std::string& value)
54 {
55  if (config_node[key].getType() == XmlRpc::XmlRpcValue::TypeString)
56  {
57  value = (std::string&)config_node[key];
58  return true;
59  }
60 
61  return false;
62 }
63 } // namespace impl
64 
65 // Server description defaults
68 const std::string ServerDescription::Default::MulticastIpAddress = "224.0.0.1";
70 
71 // Param keys
72 namespace rosparam
73 {
74 namespace keys
75 {
76 const std::string MulticastIpAddress = "optitrack_config/multicast_address";
77 const std::string CommandPort = "optitrack_config/command_port";
78 const std::string DataPort = "optitrack_config/data_port";
79 const std::string EnableOptitrack = "optitrack_config/enable_optitrack";
80 const std::string Version = "optitrack_config/version";
81 const std::string RigidBodies = "rigid_bodies";
82 const std::string PoseTopicName = "pose";
83 const std::string Pose2dTopicName = "pose2d";
84 const std::string OdomTopicName = "odom";
85 const std::string EnableTfPublisher = "tf";
86 const std::string ChildFrameId = "child_frame_id";
87 const std::string ParentFrameId = "parent_frame_id";
88 } // namespace keys
89 } // namespace rosparam
90 
92  commandPort(ServerDescription::Default::CommandPort),
94  enableOptitrack(ServerDescription::Default::EnableOptitrack),
95  multicastIpAddress(ServerDescription::Default::MulticastIpAddress)
96 {}
97 
99  ros::NodeHandle& nh,
100  ServerDescription& serverDescription,
101  PublisherConfigurations& pubConfigs)
102 {
103  // Get server cconfiguration from ROS parameter server
105  {
107  }
108  else
109  {
110  ROS_WARN_STREAM("Could not get multicast address, using default: " <<
111  serverDescription.multicastIpAddress);
112  }
113 
115  {
116  nh.getParam(rosparam::keys::CommandPort, serverDescription.commandPort);
117  }
118  else
119  {
120  ROS_WARN_STREAM("Could not get command port, using default: " <<
121  serverDescription.commandPort);
122  }
123 
125  {
127  }
128  else
129  {
130  ROS_WARN_STREAM("Could not get enable optitrack, using default: " <<
131  serverDescription.enableOptitrack);
132  }
133 
135  {
136  nh.getParam(rosparam::keys::DataPort, serverDescription.dataPort);
137  }
138  else
139  {
140  ROS_WARN_STREAM("Could not get data port, using default: " <<
141  serverDescription.dataPort);
142  }
143 
145  {
146  nh.getParam(rosparam::keys::Version, serverDescription.version);
147  }
148  else
149  {
150  ROS_WARN_STREAM("Could not get server version, using auto");
151  }
152 
153  // Parse rigid bodies section
155  {
156  XmlRpc::XmlRpcValue bodyList;
158 
159  if (bodyList.getType() == XmlRpc::XmlRpcValue::TypeStruct && bodyList.size() > 0)
160  {
162  // for (iter = bodyList.begin(); iter != bodyList.end(); ++iter) {
163  for (auto const& iter : bodyList)
164  {
165  std::string strBodyId = iter.first;
166  XmlRpc::XmlRpcValue bodyParameters = iter.second;
167 
168  if (bodyParameters.getType() == XmlRpc::XmlRpcValue::TypeStruct)
169  {
170  // Load configuration for this rigid body from ROS
171  PublisherConfiguration publisherConfig;
172  std::sscanf(strBodyId.c_str(), "%d", &publisherConfig.rigidBodyId);
173 
174  bool readPoseTopicName = impl::check_and_get_param(bodyParameters,
176 
177  if (!readPoseTopicName)
178  {
179  ROS_WARN_STREAM("Failed to parse " << rosparam::keys::PoseTopicName <<
180  " for body `" << publisherConfig.rigidBodyId << "`. Pose publishing disabled.");
181  publisherConfig.publishPose = false;
182  }
183  else
184  {
185  publisherConfig.publishPose = true;
186  }
187 
188  bool readPose2dTopicName = impl::check_and_get_param(bodyParameters,
190 
191  if (!readPose2dTopicName)
192  {
193  ROS_WARN_STREAM("Failed to parse " << rosparam::keys::Pose2dTopicName <<
194  " for body `" << publisherConfig.rigidBodyId << "`. Pose publishing disabled.");
195  publisherConfig.publishPose2d = false;
196  }
197  else
198  {
199  publisherConfig.publishPose2d = true;
200  }
201 
202  bool readOdomTopicName = impl::check_and_get_param(bodyParameters,
204 
205  if (!readOdomTopicName)
206  {
207  ROS_WARN_STREAM("Failed to parse " << rosparam::keys::OdomTopicName <<
208  " for body `" << publisherConfig.rigidBodyId << "`. Odom publishing disabled.");
209  publisherConfig.publishOdom = false;
210  }
211  else
212  {
213  publisherConfig.publishOdom = true;
214  }
215 
216  bool readEnableTfPublisher = impl::check_and_get_param(bodyParameters,
218  if (!readEnableTfPublisher)
219  {
220  ROS_WARN_STREAM("Failed to parse " << rosparam::keys::EnableTfPublisher <<
221  " for body `" << publisherConfig.enableTfPublisher << "`. Tf publishing disabled.");
222  publisherConfig.publishTf = false;
223  }
224  else
225  {
226  publisherConfig.publishTf = true;
227  }
228 
229  bool readChildFrameId = impl::check_and_get_param(bodyParameters,
230  rosparam::keys::ChildFrameId, publisherConfig.childFrameId);
231 
232  bool readParentFrameId = impl::check_and_get_param(bodyParameters,
234 
235  if (!readChildFrameId || !readParentFrameId || !publisherConfig.publishTf)
236  { if (!readEnableTfPublisher)
237  ROS_WARN_STREAM("tf is not found in the config" << rosparam::keys::EnableTfPublisher <<
238  " for body `" << publisherConfig.rigidBodyId << "`. TF publishing disabled.");
239  if (!readChildFrameId)
240  ROS_WARN_STREAM("Failed to parse " << rosparam::keys::ChildFrameId <<
241  " for body `" << publisherConfig.rigidBodyId << "`. TF publishing disabled.");
242 
243  if (!readParentFrameId)
244  ROS_WARN_STREAM("Failed to parse " << rosparam::keys::ParentFrameId <<
245  " for body `" << publisherConfig.rigidBodyId << "`. TF publishing disabled.");
246 
247  publisherConfig.publishTf = false;
248  }
249  else
250  {
251  publisherConfig.publishTf = true;
252  }
253 
254  pubConfigs.push_back(publisherConfig);
255  }
256  }
257  }
258  }
259 }
260 
261 } // namespace mocap_optitrack
const std::string MulticastIpAddress
const std::string EnableOptitrack
const std::string EnableTfPublisher
ValueStruct::iterator iterator
const std::string Pose2dTopicName
int size() const
Type const & getType() const
static void fromRosParam(ros::NodeHandle &nh, ServerDescription &serverDescription, PublisherConfigurations &pubConfigs)
static const std::string MulticastIpAddress
Definition: mocap_config.h:48
Version class containing the version information and helpers for comparison.
Definition: version.h:38
bool check_and_get_param(XmlRpc::XmlRpcValue &config_node, std::string const &key, T &value)
ROS publisher configuration.
Definition: mocap_config.h:61
#define ROS_WARN_STREAM(args)
std::vector< PublisherConfiguration > PublisherConfigurations
Definition: mocap_config.h:77
bool getParam(const std::string &key, std::string &s) const
bool hasParam(const std::string &key) const
Server communication info.
Definition: mocap_config.h:42


mocap_optitrack
Author(s): Kathrin Gräve , Alex Bencz/ , Tony Baltovski , JD Yamokoski
autogenerated on Fri Mar 26 2021 02:05:51