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  */
30 
32 #include <string>
33 #include <XmlRpcValue.h>
34 
35 namespace mocap_nokov
36 {
37 namespace impl
38 {
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 }
64 // Server description defaults
65 const std::string ServerDescription::Default::IpAddress = "10.1.1.198";
66 
67 // Param keys
68 namespace rosparam
69 {
70  namespace keys
71  {
72  const std::string ServerIpAddrss = "nokov_config/server_address";
73  const std::string Version = "nokov_config/version";
74  const std::string RigidBodies = "rigid_bodies";
75  const std::string PoseTopicName = "pose";
76  const std::string Pose2dTopicName = "pose2d";
77  const std::string OdomTopicName = "odom";
78  const std::string EnableTfPublisher = "tf";
79  const std::string ChildFrameId = "child_frame_id";
80  const std::string ParentFrameId = "parent_frame_id";
81  }
82 }
83 
85  IpAddress(ServerDescription::Default::IpAddress)
86 {}
87 
89  ros::NodeHandle& nh,
90  ServerDescription& serverDescription,
91  PublisherConfigurations& pubConfigs)
92 {
93  // Get server cconfiguration from ROS parameter server
95  {
96  nh.getParam(rosparam::keys::ServerIpAddrss, serverDescription.IpAddress);
97  }
98  else
99  {
100  ROS_WARN_STREAM("Could not get server address, using default: " <<
101  serverDescription.IpAddress);
102  }
103 
104  // if (nh.hasParam(rosparam::keys::Version))
105  // {
106  // nh.getParam(rosparam::keys::Version, serverDescription.version);
107  // }
108  // else
109  // {
110  // ROS_WARN_STREAM("Could not get server version, using auto");
111  // }
112 
114  {
115  XmlRpc::XmlRpcValue bodyList;
117 
118  if (bodyList.getType() == XmlRpc::XmlRpcValue::TypeStruct && bodyList.size() > 0)
119  {
121  // for (iter = bodyList.begin(); iter != bodyList.end(); ++iter) {
122  for (auto const& iter : bodyList)
123  {
124  std::string strBodyId = iter.first;
125  XmlRpc::XmlRpcValue bodyParameters = iter.second;
126 
127  if (bodyParameters.getType() == XmlRpc::XmlRpcValue::TypeStruct)
128  {
129  // Load configuration for this rigid body from ROS
130  PublisherConfiguration publisherConfig;
131  std::sscanf(strBodyId.c_str(), "%d", &publisherConfig.rigidBodyId);
132 
133  bool readPoseTopicName = impl::check_and_get_param(bodyParameters,
135 
136  if (!readPoseTopicName)
137  {
138  ROS_WARN_STREAM("Failed to parse " << rosparam::keys::PoseTopicName <<
139  " for body `" << publisherConfig.rigidBodyId << "`. Pose publishing disabled.");
140  publisherConfig.publishPose = false;
141  }
142  else
143  {
144  publisherConfig.publishPose = true;
145  }
146 
147  bool readPose2dTopicName = impl::check_and_get_param(bodyParameters,
149 
150  if (!readPose2dTopicName)
151  {
152  ROS_WARN_STREAM("Failed to parse " << rosparam::keys::Pose2dTopicName <<
153  " for body `" << publisherConfig.rigidBodyId << "`. Pose publishing disabled.");
154  publisherConfig.publishPose2d = false;
155  }
156  else
157  {
158  publisherConfig.publishPose2d = true;
159  }
160 
161  bool readOdomTopicName = impl::check_and_get_param(bodyParameters,
163 
164  if (!readOdomTopicName)
165  {
166  ROS_WARN_STREAM("Failed to parse " << rosparam::keys::OdomTopicName <<
167  " for body `" << publisherConfig.rigidBodyId << "`. Odom publishing disabled.");
168  publisherConfig.publishOdom = false;
169  }
170  else
171  {
172  publisherConfig.publishOdom = true;
173  }
174 
175  bool readEnableTfPublisher = impl::check_and_get_param(bodyParameters,
177  if (!readEnableTfPublisher)
178  {
179  ROS_WARN_STREAM("Failed to parse " << rosparam::keys::EnableTfPublisher <<
180  " for body `" << publisherConfig.enableTfPublisher << "`. Tf publishing disabled.");
181  publisherConfig.publishTf = false;
182  }
183  else
184  {
185  publisherConfig.publishTf = true;
186  }
187 
188  bool readChildFrameId = impl::check_and_get_param(bodyParameters,
189  rosparam::keys::ChildFrameId, publisherConfig.childFrameId);
190 
191  bool readParentFrameId = impl::check_and_get_param(bodyParameters,
193 
194  if (!readChildFrameId || !readParentFrameId || !publisherConfig.publishTf)
195  { if (!readEnableTfPublisher)
196  ROS_WARN_STREAM("tf is not found in the config" << rosparam::keys::EnableTfPublisher <<
197  " for body `" << publisherConfig.rigidBodyId << "`. TF publishing disabled.");
198  if (!readChildFrameId)
199  ROS_WARN_STREAM("Failed to parse " << rosparam::keys::ChildFrameId <<
200  " for body `" << publisherConfig.rigidBodyId << "`. TF publishing disabled.");
201 
202  if (!readParentFrameId)
203  ROS_WARN_STREAM("Failed to parse " << rosparam::keys::ParentFrameId <<
204  " for body `" << publisherConfig.rigidBodyId << "`. TF publishing disabled.");
205 
206  publisherConfig.publishTf = false;
207  }
208  else
209  {
210  publisherConfig.publishTf = true;
211  }
212 
213  pubConfigs.push_back(publisherConfig);
214  }
215  }
216  }
217  }
218 }
219 
220 }
XmlRpc::XmlRpcValue::size
int size() const
mocap_nokov::PublisherConfiguration
ROS publisher configuration.
Definition: mocap_config.h:56
mocap_nokov::PublisherConfiguration::pose2dTopicName
std::string pose2dTopicName
Definition: mocap_config.h:60
mocap_nokov::rosparam::keys::OdomTopicName
const std::string OdomTopicName
Definition: mocap_config.cpp:77
mocap_nokov::Version
\breif Version class containing the version information and helpers for comparison.
Definition: version.h:39
mocap_nokov::PublisherConfiguration::publishOdom
bool publishOdom
Definition: mocap_config.h:68
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
mocap_nokov::ServerDescription::IpAddress
std::string IpAddress
Definition: mocap_config.h:51
mocap_nokov::PublisherConfiguration::parentFrameId
std::string parentFrameId
Definition: mocap_config.h:64
mocap_nokov::ServerDescription
Server communication info.
Definition: mocap_config.h:43
mocap_nokov::PublisherConfigurations
std::vector< PublisherConfiguration > PublisherConfigurations
Definition: mocap_config.h:72
XmlRpc::XmlRpcValue::TypeStruct
TypeStruct
mocap_nokov::rosparam::keys::ParentFrameId
const std::string ParentFrameId
Definition: mocap_config.cpp:80
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
mocap_nokov::PublisherConfiguration::publishPose2d
bool publishPose2d
Definition: mocap_config.h:67
mocap_nokov::PublisherConfiguration::poseTopicName
std::string poseTopicName
Definition: mocap_config.h:59
mocap_nokov::rosparam::keys::RigidBodies
const std::string RigidBodies
Definition: mocap_config.cpp:74
mocap_nokov::PublisherConfiguration::publishPose
bool publishPose
Definition: mocap_config.h:66
XmlRpc::XmlRpcValue::TypeString
TypeString
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
mocap_nokov::PublisherConfiguration::rigidBodyId
int rigidBodyId
Definition: mocap_config.h:58
mocap_nokov::rosparam::keys::ChildFrameId
const std::string ChildFrameId
Definition: mocap_config.cpp:79
XmlRpcValue.h
XmlRpc::XmlRpcValue::iterator
ValueStruct::iterator iterator
XmlRpc::XmlRpcValue::getType
const Type & getType() const
mocap_nokov::PublisherConfiguration::childFrameId
std::string childFrameId
Definition: mocap_config.h:63
mocap_nokov::ServerDescription::Default
Definition: mocap_config.h:45
mocap_nokov::PublisherConfiguration::odomTopicName
std::string odomTopicName
Definition: mocap_config.h:61
mocap_nokov::ServerDescription::ServerDescription
ServerDescription()
Definition: mocap_config.cpp:84
mocap_nokov::rosparam::keys::PoseTopicName
const std::string PoseTopicName
Definition: mocap_config.cpp:75
mocap_nokov::ServerDescription::Default::IpAddress
static const std::string IpAddress
Definition: mocap_config.h:47
mocap_config.h
mocap_nokov::NodeConfiguration::fromRosParam
static void fromRosParam(ros::NodeHandle &nh, ServerDescription &serverDescription, PublisherConfigurations &pubConfigs)
Definition: mocap_config.cpp:88
mocap_nokov::rosparam::keys::ServerIpAddrss
const std::string ServerIpAddrss
Definition: mocap_config.cpp:72
mocap_nokov
Definition: data_model.h:39
mocap_nokov::rosparam::keys::EnableTfPublisher
const std::string EnableTfPublisher
Definition: mocap_config.cpp:78
mocap_nokov::rosparam::keys::Pose2dTopicName
const std::string Pose2dTopicName
Definition: mocap_config.cpp:76
mocap_nokov::PublisherConfiguration::publishTf
bool publishTf
Definition: mocap_config.h:69
mocap_nokov::PublisherConfiguration::enableTfPublisher
std::string enableTfPublisher
Definition: mocap_config.h:62
XmlRpc::XmlRpcValue
mocap_nokov::impl::check_and_get_param
bool check_and_get_param(XmlRpc::XmlRpcValue &config_node, std::string const &key, T &value)
Definition: mocap_config.cpp:41
ros::NodeHandle


mocap_nokov
Author(s):
autogenerated on Mon Mar 3 2025 03:08:00