GraftParameterManager.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2013, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 /*
31  * Author: Chad Rockey
32  */
33 
35 
36 
37 // Commonly used parameter loading function
38 template <std::size_t SIZE>
40  const std::string& param_name,
41  boost::array<double, SIZE>& values)
42 {
43  XmlRpc::XmlRpcValue xml_array;
44  if (nh.getParam(param_name, xml_array))
45  {
46  if (xml_array.size() == SIZE)
47  {
48  for (size_t i = 0; i < xml_array.size(); i++)
49  {
50  std::stringstream ss; // Convert the list element into doubles
51  ss << xml_array[i];
52  ss >> values[i] ? values[i] : 0;
53  }
54  return true; // loaded params into array
55  }
56  else
57  {
58  ROS_WARN("%s/%s parameter requires %d elements, skipping.",
59  nh.getNamespace().c_str(), param_name.c_str(), static_cast<int>(SIZE));
60  return false;
61  }
62  }
63  return false;
64 }
65 
66 
68  n_(n), pnh_(pnh), include_pose_(false)
69 {
70 }
71 
72 
74 {
75 }
76 
77 
79  ros::NodeHandle& tnh,
81 {
82  // Check how to use this sensor
83  bool absolute_pose, delta_pose, use_velocities;
84  double timeout;
85  tnh.param<bool>("absolute_pose", absolute_pose, false);
86  tnh.param<bool>("delta_pose", delta_pose, false);
87  tnh.param<bool>("use_velocities", use_velocities, false);
88  tnh.param<double>("timeout", timeout, 1.0);
89 
90  // Check for incompatible usage
91  if (absolute_pose == true)
92  {
93  delta_pose = false; // Should not use for both absolute position and velocity
94  }
95  if (delta_pose == true)
96  {
97  use_velocities = false; // Should not use both estimated and reported velocities
98  }
99 
100  // Apply to global state
101  include_pose_ = include_pose_ || absolute_pose;
102 
103  // Apply to sensor
104  odom->useAbsolutePose(absolute_pose);
105  odom->useDeltaPose(delta_pose);
106  odom->useVelocities(use_velocities);
107  odom->setTimeout(timeout);
108 
109  //ROS_INFO("Abs pose: %d\nDelta pose: %d\nUse Vel: %d\nTimeout: %.3f", absolute_pose, delta_pose, use_velocities, timeout);
110 
111  // Set covariances
112  boost::array<double, 36> covariance;
113  if (load_rosparam_array(tnh, "override_pose_covariance", covariance))
114  odom->setPoseCovariance(covariance);
115  if (load_rosparam_array(tnh, "override_twist_covariance", covariance))
116  odom->setTwistCovariance(covariance);
117 }
118 
120  ros::NodeHandle& tnh,
122 {
123  // Check how to use this sensor
124  bool absolute_orientation, delta_orientation, use_velocities, use_accelerations;
125  double timeout;
126  tnh.param<bool>("absolute_orientation", absolute_orientation, false);
127  tnh.param<bool>("delta_orientation", delta_orientation, false);
128  tnh.param<bool>("use_velocities", use_velocities, false);
129  tnh.param<bool>("use_accelerations", use_accelerations, false);
130  tnh.param<double>("timeout", timeout, 1.0);
131 
132  // Check for incompatible usage
133  if (absolute_orientation == true){
134  delta_orientation = false; // Should not use for both absolute position and velocity
135  }
136  if (delta_orientation == true){
137  use_velocities = false; // Should not use both estimated and reported velocities
138  }
139 
140  // Apply to global state
141  include_pose_ = include_pose_ || absolute_orientation;
142 
143  // Apply to sensor
144  //imu->useAbsoluteOrientation(absolute_orientation);
145  imu->useDeltaOrientation(delta_orientation);
146  //imu->useVelocities(use_velocities);
147  //imu->useAccelerations(use_accelerations);
148  imu->setTimeout(timeout);
149 
150  ROS_INFO("Abs orientation: %d\nDelta orientation: %d\nUse Vel: %d\nTimeout: %.3f",
151  absolute_orientation, delta_orientation, use_velocities, timeout);
152 
153  // Set covariances
154  boost::array<double, 9> covariance;
155  if (load_rosparam_array(tnh, "override_orientation_covariance", covariance))
156  imu->setOrientationCovariance(covariance);
157  if (load_rosparam_array(tnh, "override_angular_velocity_covariance", covariance))
158  imu->setAngularVelocityCovariance(covariance);
159  if (load_rosparam_array(tnh, "override_linear_acceleration_covariance", covariance))
160  imu->setLinearAccelerationCovariance(covariance);
161 }
162 
164  std::vector<boost::shared_ptr<GraftSensor> >& topics,
165  std::vector<ros::Subscriber>& subs)
166 {
167  // Filter behavior parameters
168  pnh_.param<std::string>("filter_type", filter_type_, "EKF");
169  pnh_.param<bool>("planar_output", planar_output_, true);
170 
171  pnh_.param<std::string>("parent_frame_id", parent_frame_id_, "odom");
172  pnh_.param<std::string>("child_frame_id", child_frame_id_, "base_link");
173 
174  pnh_.param<double>("freq", update_rate_, 50.0);
175  pnh_.param<double>("update_rate", update_rate_, update_rate_); // Overrides 'freq'
176  pnh_.param<double>("dt_override", dt_override_, 0.0);
177 
178  pnh_.param<bool>("publish_tf", publish_tf_, false);
179 
180  pnh_.param<int>("queue_size", queue_size_, 1);
181 
182  pnh_.param<double>("alpha", alpha_, 0.001);
183  pnh_.param<double>("kappa", kappa_, 0.0);
184  pnh_.param<double>("beta", beta_, 2.0);
185 
186  // Initial covariance
187  XmlRpc::XmlRpcValue xml_initial_covariance;
188  if (pnh_.getParam("initial_covariance", xml_initial_covariance))
189  {
190  initial_covariance_.resize(xml_initial_covariance.size());
191  for (size_t i = 0; i < xml_initial_covariance.size(); i++)
192  {
193  std::stringstream ss; // Convert the list element into doubles
194  ss << xml_initial_covariance[i];
195  ss >> initial_covariance_[i] ? initial_covariance_[i] : 0;
196  }
197  }
198 
199  // Process noise covariance
200  XmlRpc::XmlRpcValue xml_process_noise;
201  if (pnh_.getParam("process_noise", xml_process_noise))
202  {
203  process_noise_.resize(xml_process_noise.size());
204  for (size_t i = 0; i < xml_process_noise.size(); i++)
205  {
206  std::stringstream ss; // Convert the list element into doubles
207  ss << xml_process_noise[i];
208  ss >> process_noise_[i] ? process_noise_[i] : 0;
209  }
210  }
211 
212  // Read each topic config
213  try
214  {
215  XmlRpc::XmlRpcValue topic_list;
216  if (!pnh_.getParam("topics", topic_list))
217  {
218  ROS_FATAL("XmlRpc Error parsing parameters. Make sure parameters were loaded into this node's namespace.");
219  ros::shutdown();
220  }
221 
222  ROS_INFO("Number of topics: %i", topic_list.size());
223 
224  // Iterate over the map of each joint and its parameters
225  std::map<std::string, XmlRpc::XmlRpcValue>::iterator i;
226  for (i = topic_list.begin(); i != topic_list.end(); i++)
227  {
228  // Get the name of this topic. ex: base_odometry
229  std::string topic_name = i->first;
230 
231  // Set up a nodehandle in this namespace (so we don't have to deal with the XmlRpc object)
232  ros::NodeHandle tnh("~/topics/" + topic_name);
233 
234  ROS_INFO("Topic name: %s", topic_name.c_str());
235 
236  // Parse parameters according to topic type
237  std::string type;
238  if (!tnh.getParam("type", type))
239  {
240  ROS_ERROR("Could not get topic type for %s, skipping.", topic_name.c_str());
241  continue;
242  }
243 
244  ROS_INFO("Type: %s", type.c_str());
245 
246  if (type == "nav_msgs/Odometry")
247  {
248  std::string full_topic;
249  if (!tnh.getParam("topic", full_topic))
250  {
251  ROS_ERROR("Could not get full topic for %s, skipping.", topic_name.c_str());
252  continue;
253  }
254 
255  // Create Odometry object
257  odom->setName(topic_name);
258  topics.push_back(odom);
259 
260  // Should we specify nodelay so that packets arrive without delay
261  ros::TransportHints hints;
262  bool tcp_nodelay;
263  if (tnh.getParam("no_delay", tcp_nodelay))
264  {
265  if (tcp_nodelay)
266  hints.tcpNoDelay();
267  }
268 
269  // Subscribe to topic
270  ros::Subscriber sub = n_.subscribe(full_topic, queue_size_, &GraftOdometryTopic::callback, odom, hints);
271  subs.push_back(sub);
272 
273  // Parse rest of parameters
275  }
276  else if (type == "sensor_msgs/Imu")
277  {
278  std::string full_topic;
279  if (!tnh.getParam("topic", full_topic))
280  {
281  ROS_ERROR("Could not get full topic for %s, skipping.", topic_name.c_str());
282  continue;
283  }
284 
285  // Create Imu object
287  imu->setName(topic_name);
288  topics.push_back(imu);
289 
290  // Should we specify nodelay so that packets arrive without delay
291  ros::TransportHints hints;
292  bool tcp_nodelay;
293  if (tnh.getParam("no_delay", tcp_nodelay))
294  {
295  if (tcp_nodelay)
296  hints.tcpNoDelay();
297  }
298 
299  // Subscribe to topic
300  ros::Subscriber sub = n_.subscribe(full_topic, queue_size_, &GraftImuTopic::callback, imu, hints);
301  subs.push_back(sub);
302 
303  // Parse rest of parameters
305  }
306  else
307  {
308  ROS_WARN("Unknown type: %s Not parsing configuration.", type.c_str());
309  }
310  }
311  }
312  catch(...)
313  {
314  ROS_FATAL("XmlRpc Error parsing parameters. Cannot start.");
315  ros::shutdown();
316  }
317 }
318 
319 
321 {
322  return filter_type_;
323 }
324 
325 
327 {
328  return planar_output_;
329 }
330 
331 
333 {
334  return parent_frame_id_;
335 }
336 
337 
339 {
340  return child_frame_id_;
341 }
342 
343 
345 {
346  return update_rate_;
347 }
348 
349 
351 {
352  return update_topic_;
353 }
354 
355 
357 {
358  return dt_override_;
359 }
360 
361 
363 {
364  return queue_size_;
365 }
366 
367 
369 {
370  return include_pose_;
371 }
372 
373 
375 {
376  return publish_tf_;
377 }
378 
379 
381 {
382  return initial_covariance_;
383 }
384 
385 
387 {
388  return process_noise_;
389 }
390 
391 
393 {
394  return alpha_;
395 }
396 
397 
399 {
400  return kappa_;
401 }
402 
403 
405 {
406  return beta_;
407 }
XmlRpc::XmlRpcValue::size
int size() const
GraftParameterManager::publish_tf_
bool publish_tf_
Definition: GraftParameterManager.h:99
GraftParameterManager::getChildFrameID
std::string getChildFrameID()
Definition: GraftParameterManager.cpp:338
GraftParameterManager::getdtOveride
double getdtOveride()
Definition: GraftParameterManager.cpp:356
GraftParameterManager::getBeta
double getBeta()
Definition: GraftParameterManager.cpp:404
boost::shared_ptr
GraftParameterManager::getInitialCovariance
std::vector< double > getInitialCovariance()
Definition: GraftParameterManager.cpp:380
load_rosparam_array
bool load_rosparam_array(ros::NodeHandle &nh, const std::string &param_name, boost::array< double, SIZE > &values)
Definition: GraftParameterManager.cpp:39
GraftParameterManager::~GraftParameterManager
~GraftParameterManager()
Definition: GraftParameterManager.cpp:73
GraftParameterManager::kappa_
double kappa_
Definition: GraftParameterManager.h:103
GraftParameterManager.h
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
GraftParameterManager::process_noise_
std::vector< double > process_noise_
Definition: GraftParameterManager.h:101
GraftParameterManager::loadParameters
void loadParameters(std::vector< boost::shared_ptr< GraftSensor > > &topics, std::vector< ros::Subscriber > &subs)
Definition: GraftParameterManager.cpp:163
ros::TransportHints
ros::shutdown
ROSCPP_DECL void shutdown()
GraftParameterManager::getPublishTF
bool getPublishTF()
Definition: GraftParameterManager.cpp:374
GraftOdometryTopic::callback
void callback(const nav_msgs::Odometry::ConstPtr &msg)
Definition: GraftOdometryTopic.cpp:51
GraftParameterManager::getAlpha
double getAlpha()
Definition: GraftParameterManager.cpp:392
GraftParameterManager::getFilterType
std::string getFilterType()
Definition: GraftParameterManager.cpp:320
GraftParameterManager::alpha_
double alpha_
Definition: GraftParameterManager.h:102
GraftParameterManager::getQueueSize
int getQueueSize()
Definition: GraftParameterManager.cpp:362
GraftParameterManager::queue_size_
int queue_size_
Definition: GraftParameterManager.h:98
ros::TransportHints::tcpNoDelay
TransportHints & tcpNoDelay(bool nodelay=true)
GraftParameterManager::update_rate_
double update_rate_
Definition: GraftParameterManager.h:95
GraftParameterManager::getPlanarOutput
bool getPlanarOutput()
Definition: GraftParameterManager.cpp:326
GraftParameterManager::getIncludePose
bool getIncludePose()
Definition: GraftParameterManager.cpp:368
GraftParameterManager::GraftParameterManager
GraftParameterManager(ros::NodeHandle n, ros::NodeHandle pnh)
Definition: GraftParameterManager.cpp:67
ROS_WARN
#define ROS_WARN(...)
GraftParameterManager::beta_
double beta_
Definition: GraftParameterManager.h:104
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
GraftImuTopic::callback
void callback(const sensor_msgs::Imu::ConstPtr &msg)
Definition: GraftImuTopic.cpp:52
XmlRpc::XmlRpcValue::end
iterator end()
ROS_FATAL
#define ROS_FATAL(...)
GraftParameterManager::parseSensorMsgsIMUParameters
void parseSensorMsgsIMUParameters(ros::NodeHandle &tnh, boost::shared_ptr< GraftImuTopic > &imu)
Definition: GraftParameterManager.cpp:119
GraftParameterManager::planar_output_
bool planar_output_
Definition: GraftParameterManager.h:92
GraftParameterManager::getProcessNoise
std::vector< double > getProcessNoise()
Definition: GraftParameterManager.cpp:386
GraftImuTopic
Definition: GraftImuTopic.h:46
GraftParameterManager::getKappa
double getKappa()
Definition: GraftParameterManager.cpp:398
GraftParameterManager::parseNavMsgsOdometryParameters
void parseNavMsgsOdometryParameters(ros::NodeHandle &tnh, boost::shared_ptr< GraftOdometryTopic > &odom)
Definition: GraftParameterManager.cpp:78
values
std::vector< double > values
GraftParameterManager::getUpdateRate
double getUpdateRate()
Definition: GraftParameterManager.cpp:344
ROS_ERROR
#define ROS_ERROR(...)
GraftParameterManager::filter_type_
std::string filter_type_
Definition: GraftParameterManager.h:91
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
GraftParameterManager::initial_covariance_
std::vector< double > initial_covariance_
Definition: GraftParameterManager.h:100
GraftParameterManager::include_pose_
bool include_pose_
Definition: GraftParameterManager.h:107
SIZE
#define SIZE
Definition: GraftUKFAbsolute.h:47
GraftParameterManager::pnh_
ros::NodeHandle pnh_
Definition: GraftParameterManager.h:89
GraftParameterManager::dt_override_
double dt_override_
Definition: GraftParameterManager.h:97
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
XmlRpc::XmlRpcValue::begin
iterator begin()
GraftParameterManager::child_frame_id_
std::string child_frame_id_
Definition: GraftParameterManager.h:94
ROS_INFO
#define ROS_INFO(...)
GraftParameterManager::getUpdateTopic
std::string getUpdateTopic()
Definition: GraftParameterManager.cpp:350
GraftParameterManager::update_topic_
std::string update_topic_
Definition: GraftParameterManager.h:96
XmlRpc::XmlRpcValue
ros::NodeHandle
ros::Subscriber
GraftParameterManager::parent_frame_id_
std::string parent_frame_id_
Definition: GraftParameterManager.h:93
GraftParameterManager::getParentFrameID
std::string getParentFrameID()
Definition: GraftParameterManager.cpp:332
GraftOdometryTopic
Definition: GraftOdometryTopic.h:46
GraftParameterManager::n_
ros::NodeHandle n_
Definition: GraftParameterManager.h:88


graft
Author(s): Chad Rockey
autogenerated on Wed Mar 2 2022 00:20:33