Skip to content
Snippets Groups Projects
Commit c333d175 authored by Laia Freixas Mateu's avatar Laia Freixas Mateu
Browse files

changed topic from odometry/filtered to /filtered_odometry

parent cc7ee03e
No related branches found
No related tags found
1 merge request!3Kalman filter, solves #2
......@@ -53,7 +53,6 @@ class HtcViveTrackerAlgNode : public algorithm_base::IriBaseAlgorithm<HtcViveTra
// [subscriber attributes]
ros::Publisher pose_publisher_;
ros::Publisher vo_publisher_;
tf::TransformListener tf_listener_;
//
......
......@@ -9,6 +9,7 @@
<node pkg="robot_localization" type="ekf_localization_node" name="ekf_se" clear_params="true">
<rosparam command="load" file="$(find iri_htc_vive_tracker)/params/ekf_htcvive.yaml" />
<remap from="odometry/filtered" to="filtered_odometry"/>
</node>
</launch>
......@@ -33,7 +33,6 @@ HtcViveTrackerAlgNode::HtcViveTrackerAlgNode(void) :
this->source_frame_name_ = "chaperone";
pose_publisher_ = this->public_node_handle_.advertise<geometry_msgs::PoseStamped>("new_pose",100);
vo_publisher_ = this->public_node_handle_.advertise<nav_msgs::Odometry>("vo",100);
......@@ -93,7 +92,6 @@ void HtcViveTrackerAlgNode::PublishPoseOfDeviceToFollow(void){
Velocity device_vel = this->alg_.GetDeviceVelocity(this->target_frame_name_);
nav_msgs::Odometry current_vo = this->CreateOdometryFromPoseVel(tf_pose, device_vel);
this->vo_publisher_.publish(current_vo);
this->pose_publisher_.publish(tf_pose);
}
else {
ROS_INFO ("Transform not possible");
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment