Skip to content
Open
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
4 changes: 2 additions & 2 deletions mocap_base/src/MoCapDriverBase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -122,8 +122,8 @@ void Subject::processNewMeasurement(
}

// Transform matrix from parent to child frame
Isometry3d tf_parent2child = Isometry3d(Translation3d(m_position) * m_attitude);

Isometry3d tf_child2parent = Isometry3d(Translation3d(m_position) * m_attitude);
Isometry3d tf_parent2child = tf_child2parent.inverse();
status = TRACKED;
// Perfrom the kalman filter

Expand Down
18 changes: 6 additions & 12 deletions mocap_qualisys/src/QualisysDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,26 +46,18 @@ bool QualisysDriver::init() {
nh->declare_parameter("udp_port", -1);
nh->declare_parameter("qtm_protocol_version", 18);


std::string server_address;
nh->get_parameter_or("server_address", server_address, string(""));
int base_port;
nh->get_parameter_or("server_base_port", base_port, 22222);
vector<string> model_list;
nh->get_parameter_or("model_list", model_list, vector<string>(0));
int unsigned_frame_rate;
nh->get_parameter_or("frame_rate", unsigned_frame_rate, 0);
unsigned int frame_rate = unsigned_frame_rate > 0 ? unsigned_frame_rate : 0;
frame_rate = unsigned_frame_rate > 0 ? unsigned_frame_rate : 0;

double max_accel;
nh->get_parameter_or("max_accel", max_accel, 10.0);
bool publish_tf;
nh->get_parameter_or("publish_tf", publish_tf, false);
std::string fixed_frame_id;
nh->get_parameter_or("fixed_frame_id", fixed_frame_id, string("mocap"));
int int_udp_port;
nh->get_parameter_or("udp_port", int_udp_port, -1);
int qtm_protocol_version;
nh->get_parameter_or("qtm_protocol_version", qtm_protocol_version, 18);

if (server_address.empty()){
Expand Down Expand Up @@ -201,6 +193,7 @@ bool QualisysDriver::run() {
}

void QualisysDriver::handleFrame() {

// Number of rigid bodies
int body_count = prt_packet->Get6DOFBodyCount();
// Compute the timestamp
Expand Down Expand Up @@ -240,6 +233,7 @@ void QualisysDriver::handleFrame() {
}

void QualisysDriver::handleSubject(int sub_idx) {

// Name of the subject
string subject_name(port_protocol.Get6DOFBodyName(sub_idx));
// Pose of the subject
Expand Down Expand Up @@ -284,7 +278,6 @@ void QualisysDriver::handleSubject(int sub_idx) {
// Publish tf if requred
if (publish_tf &&
subjects.at(subject_name)->getStatus() == Subject::TRACKED) {

Quaterniond att = subjects.at(subject_name)->getAttitude();
Vector3d pos = subjects.at(subject_name)->getPosition();
// tf2::Quaternion att_tf;
Expand All @@ -304,9 +297,10 @@ void QualisysDriver::handleSubject(int sub_idx) {


geometry_msgs::msg::TransformStamped stamped_transform;
stamped_transform.header.stamp = rclcpp::Time(time);
// stamped_transform.header.stamp = rclcpp::Time(time);
stamped_transform.header.stamp = rclcpp::Clock().now();
stamped_transform.header.frame_id = fixed_frame_id;
stamped_transform.child_frame_id = subject_name;
stamped_transform.child_frame_id = subject_name + "/" + "base_link";

stamped_transform.transform.translation.x = pos.x();
stamped_transform.transform.translation.y = pos.y();
Expand Down
2 changes: 1 addition & 1 deletion mocap_qualisys/src/qualisys.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
int main(int argc, char *argv[]) {

rclcpp::init(argc, argv);
auto nh = rclcpp::Node::make_shared("mocal_qualisys_node");
auto nh = rclcpp::Node::make_shared("mocap_qualisys_node");

mocap::QualisysDriver driver(nh);
if(!driver.init()) {
Expand Down