Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add option to use VRPN timestamps rather than generating them again #7

Merged
merged 5 commits into from
Jan 12, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,7 @@ file with custom configurations.
system default QoS which is reliable (default: `true`)
- `multi_sensor (bool)` -- set to true if there are more than one sensor (frame) reporting on
the same object (default: `false`)
- `use_vrpn_timestamps (bool)` -- use timestamps coming from VRPN. This ensures that the interval between frames timestamps is not modified (default: `false`)

### Acknowledgement
Some ideas are borrowed from the well known
Expand Down
1 change: 1 addition & 0 deletions config/client.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -6,3 +6,4 @@
update_freq: 100.
refresh_freq: 1.
multi_sensor: false
use_vrpn_timestamps: false
4 changes: 4 additions & 0 deletions include/vrpn_mocap/tracker.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@
#include "vrpn_Connection.h"
#include "vrpn_Tracker.h"

#include "builtin_interfaces/msg/time.hpp"
#include "geometry_msgs/msg/accel_stamped.hpp"
#include "geometry_msgs/msg/pose_stamped.hpp"
#include "geometry_msgs/msg/twist_stamped.hpp"
Expand Down Expand Up @@ -100,6 +101,7 @@ class Tracker : public rclcpp::Node
const bool multi_sensor_;
const std::string frame_id_;
const bool sensor_data_qos_;
const bool use_vrpn_timestamps_;
const std::shared_ptr<vrpn_Connection> connection_;

vrpn_Tracker_Remote vrpn_tracker_;
Expand Down Expand Up @@ -139,6 +141,8 @@ class Tracker : public rclcpp::Node
return pubs->at(sensor_idx);
}

builtin_interfaces::msg::Time GetTimestamp(struct timeval vrpn_timestamp);

static void VRPN_CALLBACK HandlePose(void * tracker, const vrpn_TRACKERCB tracker_pose);
static void VRPN_CALLBACK HandleTwist(void * tracker, const vrpn_TRACKERVELCB tracker_vel);
static void VRPN_CALLBACK HandleAccel(void * tracker, const vrpn_TRACKERACCCB tracker_acc);
Expand Down
1 change: 1 addition & 0 deletions src/client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,7 @@ Client::Client(const std::string & name)
mainloop_timer_ = this->create_wall_timer(1s / update_freq, std::bind(&Client::MainLoop, this));

this->declare_parameter("sensor_data_qos", true);
this->declare_parameter("use_vrpn_timestamps", false);
}

std::string Client::ParseHost()
Expand Down
20 changes: 17 additions & 3 deletions src/tracker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,7 @@ Tracker::Tracker(const std::string & tracker_name)
multi_sensor_(declare_parameter("multi_sensor", false)),
frame_id_(declare_parameter("frame_id", "world")),
sensor_data_qos_(declare_parameter("sensor_data_qos", true)),
use_vrpn_timestamps_(declare_parameter("use_vrpn_timestamps", false)),
vrpn_tracker_(name_.c_str())
{
Init();
Expand All @@ -70,6 +71,7 @@ Tracker::Tracker(
multi_sensor_(base_node.get_parameter("multi_sensor").as_bool()),
frame_id_(base_node.get_parameter("frame_id").as_string()),
sensor_data_qos_(base_node.get_parameter("sensor_data_qos").as_bool()),
use_vrpn_timestamps_(base_node.get_parameter("use_vrpn_timestamps").as_bool()),
vrpn_tracker_(name_.c_str(), connection.get())
{
Init();
Expand All @@ -96,6 +98,18 @@ void Tracker::Init()

void Tracker::MainLoop() {vrpn_tracker_.mainloop();}

builtin_interfaces::msg::Time Tracker::GetTimestamp(struct timeval vrpn_timestamp)
{
if (this->use_vrpn_timestamps_) {
builtin_interfaces::msg::Time stamp;
stamp.sec = vrpn_timestamp.tv_sec;
stamp.nanosec = vrpn_timestamp.tv_usec * 1000;

return stamp;
}
return this->get_clock()->now();
}

void VRPN_CALLBACK Tracker::HandlePose(void * data, const vrpn_TRACKERCB tracker_pose)
{
Tracker * tracker = static_cast<Tracker *>(data);
Expand All @@ -107,7 +121,7 @@ void VRPN_CALLBACK Tracker::HandlePose(void * data, const vrpn_TRACKERCB tracker
// populate message
PoseStamped msg;
msg.header.frame_id = tracker->frame_id_;
msg.header.stamp = tracker->get_clock()->now();
msg.header.stamp = tracker->GetTimestamp(tracker_pose.msg_time);

msg.pose.position.x = tracker_pose.pos[0];
msg.pose.position.y = tracker_pose.pos[1];
Expand All @@ -132,7 +146,7 @@ void VRPN_CALLBACK Tracker::HandleTwist(void * data, const vrpn_TRACKERVELCB tra
// populate message
TwistStamped msg;
msg.header.frame_id = tracker->frame_id_;
msg.header.stamp = tracker->get_clock()->now();
msg.header.stamp = tracker->GetTimestamp(tracker_twist.msg_time);

msg.twist.linear.x = tracker_twist.vel[0];
msg.twist.linear.y = tracker_twist.vel[1];
Expand Down Expand Up @@ -161,7 +175,7 @@ void VRPN_CALLBACK Tracker::HandleAccel(void * data, const vrpn_TRACKERACCCB tra
// populate message
AccelStamped msg;
msg.header.frame_id = tracker->frame_id_;
msg.header.stamp = tracker->get_clock()->now();
msg.header.stamp = tracker->GetTimestamp(tracker_accel.msg_time);

msg.accel.linear.x = tracker_accel.acc[0];
msg.accel.linear.y = tracker_accel.acc[1];
Expand Down
Loading