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

Use configured frame IDs #14

Merged
merged 1 commit into from
Jun 11, 2014
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
12 changes: 9 additions & 3 deletions src/graft_ukf_absolute.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,9 @@ nav_msgs::Odometry odom_;
bool publish_tf_;
boost::shared_ptr<tf::TransformBroadcaster> broadcaster_;

std::string parent_frame_id_;
std::string child_frame_id_;

void publishTF(const nav_msgs::Odometry& msg){
geometry_msgs::TransformStamped tf;
tf.header.stamp = msg.header.stamp;
Expand All @@ -76,8 +79,8 @@ void timer_callback(const ros::TimerEvent& event){

// Update Odometry
odom_.header.stamp = ros::Time::now();
odom_.header.frame_id = "map";
odom_.child_frame_id = "base_link";
odom_.header.frame_id = parent_frame_id_;
odom_.child_frame_id = child_frame_id_;
odom_.pose.pose = state.pose;
odom_.twist.twist = state.twist;
odom_pub.publish(odom_);
Expand All @@ -102,6 +105,9 @@ int main(int argc, char **argv)

publish_tf_ = manager.getPublishTF();

parent_frame_id_ = manager.getParentFrameID();
child_frame_id_ = manager.getChildFrameID();

// Set up the E
std::vector<double> initial_covariance = manager.getInitialCovariance();
std::vector<double> Q = manager.getProcessNoise();
Expand Down Expand Up @@ -136,4 +142,4 @@ int main(int argc, char **argv)

// Spin
ros::spin();
}
}
12 changes: 9 additions & 3 deletions src/graft_ukf_attitude.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,9 @@ nav_msgs::Odometry odom_;
bool publish_tf_;
boost::shared_ptr<tf::TransformBroadcaster> broadcaster_;

std::string parent_frame_id_;
std::string child_frame_id_;

void publishTF(const nav_msgs::Odometry& msg){
geometry_msgs::TransformStamped tf;
tf.header.stamp = msg.header.stamp;
Expand All @@ -75,8 +78,8 @@ void timer_callback(const ros::TimerEvent& event){
state_pub.publish(state);

odom_.header.stamp = ros::Time::now();
odom_.header.frame_id = "odom_fused_ukfv";
odom_.child_frame_id = "base_link";
odom_.header.frame_id = parent_frame_id_;
odom_.child_frame_id = child_frame_id_;
odom_.pose.pose.orientation = state.pose.orientation;
odom_.twist.twist.angular = state.twist.angular;

Expand All @@ -102,6 +105,9 @@ int main(int argc, char **argv)

publish_tf_ = manager.getPublishTF();

parent_frame_id_ = manager.getParentFrameID();
child_frame_id_ = manager.getChildFrameID();

// Set up the E
std::vector<double> initial_covariance = manager.getInitialCovariance();
std::vector<double> Q = manager.getProcessNoise();
Expand Down Expand Up @@ -136,4 +142,4 @@ int main(int argc, char **argv)

// Spin
ros::spin();
}
}
12 changes: 9 additions & 3 deletions src/graft_ukf_velocity.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,9 @@ nav_msgs::Odometry odom_;
bool publish_tf_;
boost::shared_ptr<tf::TransformBroadcaster> broadcaster_;

std::string parent_frame_id_;
std::string child_frame_id_;

void publishTF(const nav_msgs::Odometry& msg){
geometry_msgs::TransformStamped tf;
tf.header.stamp = msg.header.stamp;
Expand All @@ -75,8 +78,8 @@ void timer_callback(const ros::TimerEvent& event){
state_pub.publish(state);

odom_.header.stamp = ros::Time::now();
odom_.header.frame_id = "odom_fused_ukfv";
odom_.child_frame_id = "base_link";
odom_.header.frame_id = parent_frame_id_;
odom_.child_frame_id = child_frame_id_;
odom_.twist.twist.linear.x = state.twist.linear.x;
odom_.twist.twist.linear.y = state.twist.linear.y;
odom_.twist.twist.angular.z = state.twist.angular.z;
Expand Down Expand Up @@ -123,6 +126,9 @@ int main(int argc, char **argv)

publish_tf_ = manager.getPublishTF();

parent_frame_id_ = manager.getParentFrameID();
child_frame_id_ = manager.getChildFrameID();

// Set up the E
std::vector<double> initial_covariance = manager.getInitialCovariance();
std::vector<double> Q = manager.getProcessNoise();
Expand Down Expand Up @@ -157,4 +163,4 @@ int main(int argc, char **argv)

// Spin
ros::spin();
}
}