38 template <std::
size_t SIZE>
40 const std::string& param_name,
41 boost::array<double, SIZE>& values)
44 if (nh.
getParam(param_name, xml_array))
48 for (
size_t i = 0; i < xml_array.
size(); i++)
58 ROS_WARN(
"%s/%s parameter requires %d elements, skipping.",
68 n_(n), pnh_(pnh), include_pose_(false)
83 bool absolute_pose, delta_pose, use_velocities;
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);
91 if (absolute_pose ==
true)
95 if (delta_pose ==
true)
97 use_velocities =
false;
104 odom->useAbsolutePose(absolute_pose);
105 odom->useDeltaPose(delta_pose);
106 odom->useVelocities(use_velocities);
107 odom->setTimeout(timeout);
112 boost::array<double, 36> covariance;
114 odom->setPoseCovariance(covariance);
116 odom->setTwistCovariance(covariance);
124 bool absolute_orientation, delta_orientation, use_velocities, use_accelerations;
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);
133 if (absolute_orientation ==
true){
134 delta_orientation =
false;
136 if (delta_orientation ==
true){
137 use_velocities =
false;
145 imu->useDeltaOrientation(delta_orientation);
148 imu->setTimeout(timeout);
150 ROS_INFO(
"Abs orientation: %d\nDelta orientation: %d\nUse Vel: %d\nTimeout: %.3f",
151 absolute_orientation, delta_orientation, use_velocities, timeout);
154 boost::array<double, 9> covariance;
156 imu->setOrientationCovariance(covariance);
158 imu->setAngularVelocityCovariance(covariance);
160 imu->setLinearAccelerationCovariance(covariance);
165 std::vector<ros::Subscriber>& subs)
188 if (
pnh_.
getParam(
"initial_covariance", xml_initial_covariance))
191 for (
size_t i = 0; i < xml_initial_covariance.
size(); i++)
193 std::stringstream ss;
194 ss << xml_initial_covariance[i];
204 for (
size_t i = 0; i < xml_process_noise.
size(); i++)
206 std::stringstream ss;
207 ss << xml_process_noise[i];
218 ROS_FATAL(
"XmlRpc Error parsing parameters. Make sure parameters were loaded into this node's namespace.");
225 std::map<std::string, XmlRpc::XmlRpcValue>::iterator i;
226 for (i = topic_list.
begin(); i != topic_list.
end(); i++)
229 std::string topic_name = i->first;
234 ROS_INFO(
"Topic name: %s", topic_name.c_str());
240 ROS_ERROR(
"Could not get topic type for %s, skipping.", topic_name.c_str());
246 if (type ==
"nav_msgs/Odometry")
248 std::string full_topic;
249 if (!tnh.
getParam(
"topic", full_topic))
251 ROS_ERROR(
"Could not get full topic for %s, skipping.", topic_name.c_str());
257 odom->setName(topic_name);
258 topics.push_back(odom);
263 if (tnh.
getParam(
"no_delay", tcp_nodelay))
276 else if (type ==
"sensor_msgs/Imu")
278 std::string full_topic;
279 if (!tnh.
getParam(
"topic", full_topic))
281 ROS_ERROR(
"Could not get full topic for %s, skipping.", topic_name.c_str());
287 imu->setName(topic_name);
288 topics.push_back(imu);
293 if (tnh.
getParam(
"no_delay", tcp_nodelay))
308 ROS_WARN(
"Unknown type: %s Not parsing configuration.", type.c_str());
314 ROS_FATAL(
"XmlRpc Error parsing parameters. Cannot start.");