39 #include <unordered_set>
44 std::unordered_set<std::string> name_blacklist_({
"VRPN Control"});
55 return ! ( isalpha(c) || c ==
'/' || c ==
'~' );
60 return ! ( isalnum(c) || c ==
'/' || c ==
'_' );
69 if (clean_name.size() > 0)
71 int start_subsequent = 1;
74 clean_name = clean_name.substr(1);
78 clean_name.erase( std::remove_if( clean_name.begin() + start_subsequent, clean_name.end(),
isInvalidSubsequentCharInName ), clean_name.end() );
81 init(clean_name, nh,
false);
86 std::string tracker_address;
88 tracker_remote_ = std::make_shared<vrpn_Tracker_Remote>(tracker_address.c_str());
112 std::string frame_id;
113 nh.
param<std::string>(
"frame_id", frame_id,
"world");
120 if (create_mainloop_timer)
122 double update_frequency;
123 nh.
param<
double>(
"update_frequency", update_frequency, 100.0);
147 std::size_t sensor_index(0);
152 sensor_index =
static_cast<std::size_t
>(tracker_pose.sensor);
156 if (tracker->
pose_pubs_.size() <= sensor_index)
160 pose_pub = &(tracker->
pose_pubs_[sensor_index]);
164 *pose_pub = nh.
advertise<geometry_msgs::PoseStamped>(
"pose", 1);
171 tracker->
pose_msg_.header.stamp.sec = tracker_pose.msg_time.tv_sec;
172 tracker->
pose_msg_.header.stamp.nsec = tracker_pose.msg_time.tv_usec * 1000;
179 tracker->
pose_msg_.pose.position.x = tracker_pose.pos[0];
180 tracker->
pose_msg_.pose.position.y = tracker_pose.pos[1];
181 tracker->
pose_msg_.pose.position.z = tracker_pose.pos[2];
183 tracker->
pose_msg_.pose.orientation.x = tracker_pose.quat[0];
184 tracker->
pose_msg_.pose.orientation.y = tracker_pose.quat[1];
185 tracker->
pose_msg_.pose.orientation.z = tracker_pose.quat[2];
186 tracker->
pose_msg_.pose.orientation.w = tracker_pose.quat[3];
232 std::size_t sensor_index(0);
237 sensor_index =
static_cast<std::size_t
>(tracker_twist.sensor);
249 *twist_pub = nh.
advertise<geometry_msgs::TwistStamped>(
"twist", 1);
256 tracker->
twist_msg_.header.stamp.sec = tracker_twist.msg_time.tv_sec;
257 tracker->
twist_msg_.header.stamp.nsec = tracker_twist.msg_time.tv_usec * 1000;
264 tracker->
twist_msg_.twist.linear.x = tracker_twist.vel[0];
265 tracker->
twist_msg_.twist.linear.y = tracker_twist.vel[1];
266 tracker->
twist_msg_.twist.linear.z = tracker_twist.vel[2];
268 double roll, pitch, yaw;
270 tf2::Quaternion(tracker_twist.vel_quat[0], tracker_twist.vel_quat[1], tracker_twist.vel_quat[2],
271 tracker_twist.vel_quat[3]));
272 rot_mat.
getRPY(roll, pitch, yaw);
287 std::size_t sensor_index(0);
292 sensor_index =
static_cast<std::size_t
>(tracker_accel.sensor);
304 *accel_pub = nh.
advertise<geometry_msgs::TwistStamped>(
"accel", 1);
311 tracker->
accel_msg_.header.stamp.sec = tracker_accel.msg_time.tv_sec;
312 tracker->
accel_msg_.header.stamp.nsec = tracker_accel.msg_time.tv_usec * 1000;
319 tracker->
accel_msg_.accel.linear.x = tracker_accel.acc[0];
320 tracker->
accel_msg_.accel.linear.y = tracker_accel.acc[1];
321 tracker->
accel_msg_.accel.linear.z = tracker_accel.acc[2];
323 double roll, pitch, yaw;
325 tf2::Quaternion(tracker_accel.acc_quat[0], tracker_accel.acc_quat[1], tracker_accel.acc_quat[2],
326 tracker_accel.acc_quat[3]));
327 rot_mat.
getRPY(roll, pitch, yaw);
344 connection_ = std::shared_ptr<vrpn_Connection>(vrpn_get_connection_by_name(
host_.c_str()));
347 double update_frequency;
348 private_nh.
param<
double>(
"update_frequency", update_frequency, 100.0);
351 double refresh_tracker_frequency;
352 private_nh.
param<
double>(
"refresh_tracker_frequency", refresh_tracker_frequency, 0.0);
354 if (refresh_tracker_frequency > 0.0)
360 std::vector<std::string> param_tracker_names_;
361 if (private_nh.
getParam(
"trackers", param_tracker_names_))
363 for (std::vector<std::string>::iterator it = param_tracker_names_.begin();
364 it != param_tracker_names_.end(); ++it)
373 std::stringstream host_stream;
377 host_nh.
param<std::string>(
"server", server,
"localhost");
378 host_stream << server;
382 host_stream <<
":" << port;
384 return host_stream.str();
392 ROS_WARN(
"VRPN connection is not 'doing okay'");
396 it->second->mainloop();