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

Addition of parameter to extract odom frame only generated by cartographer. #1813

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
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
11 changes: 10 additions & 1 deletion cartographer_ros/cartographer_ros/node.cc
Original file line number Diff line number Diff line change
Expand Up @@ -306,14 +306,23 @@ void Node::PublishLocalTrajectoryData(const ::ros::TimerEvent& timer_event) {
stamped_transforms.push_back(stamped_transform);

tf_broadcaster_.sendTransform(stamped_transforms);
} else {
} else if(!trajectory_data.trajectory_options.provide_odom_frame && !trajectory_data.trajectory_options.provide_odom_frame_only) {
stamped_transform.header.frame_id = node_options_.map_frame;
stamped_transform.child_frame_id =
trajectory_data.trajectory_options.published_frame;
stamped_transform.transform = ToGeometryMsgTransform(
tracking_to_map * (*trajectory_data.published_to_tracking));
tf_broadcaster_.sendTransform(stamped_transform);
}
else if(!trajectory_data.trajectory_options.provide_odom_frame && trajectory_data.trajectory_options.provide_odom_frame_only) {
stamped_transform.header.frame_id =
trajectory_data.trajectory_options.odom_frame;
stamped_transform.child_frame_id =
trajectory_data.trajectory_options.published_frame;
stamped_transform.transform = ToGeometryMsgTransform(
tracking_to_local * (*trajectory_data.published_to_tracking));
tf_broadcaster_.sendTransform(stamped_transform);
}
}
if (node_options_.publish_tracked_pose) {
::geometry_msgs::PoseStamped pose_msg;
Expand Down
2 changes: 2 additions & 0 deletions cartographer_ros/cartographer_ros/trajectory_options.cc
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,8 @@ TrajectoryOptions CreateTrajectoryOptions(
options.odom_frame = lua_parameter_dictionary->GetString("odom_frame");
options.provide_odom_frame =
lua_parameter_dictionary->GetBool("provide_odom_frame");
options.provide_odom_frame_only =
lua_parameter_dictionary->GetBool("provide_odom_frame_only");
options.use_odometry = lua_parameter_dictionary->GetBool("use_odometry");
options.use_nav_sat = lua_parameter_dictionary->GetBool("use_nav_sat");
options.use_landmarks = lua_parameter_dictionary->GetBool("use_landmarks");
Expand Down
1 change: 1 addition & 0 deletions cartographer_ros/cartographer_ros/trajectory_options.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@ struct TrajectoryOptions {
std::string published_frame;
std::string odom_frame;
bool provide_odom_frame;
bool provide_odom_frame_only;
bool use_odometry;
bool use_nav_sat;
bool use_landmarks;
Expand Down
4 changes: 4 additions & 0 deletions docs/source/configuration.rst
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,10 @@ provide_odom_frame
If enabled, the local, non-loop-closed, continuous pose will be published as
the *odom_frame* in the *map_frame*.

provide_odom_frame_only
If enable, the local, non-loop-closed, continuous pose will be published with
*odom_frame* as root.

publish_frame_projected_to_2d
If enabled, the published pose will be restricted to a pure 2D pose (no roll,
pitch, or z-offset). This prevents potentially unwanted out-of-plane poses in
Expand Down
5 changes: 5 additions & 0 deletions docs/source/ros_api.rst
Original file line number Diff line number Diff line change
Expand Up @@ -141,6 +141,11 @@ If *provide_odom_frame* is enabled in the :doc:`configuration`, additionally a c
(i.e. unaffected by loop closure) transform between the :doc:`configured
<configuration>` *odom_frame* and *published_frame* will be provided.

If *provide_odom_frame_only* is enabled in the :doc:`configuration`,a continuous
(i.e. unaffected by loop closure) transform between the :doc:`configured
<configuration>` *odom_frame* and *published_frame* will be provided. No transform
between *map_frame* and *odom_frame* will be provided in this case.

.. _robot_state_publisher: http://wiki.ros.org/robot_state_publisher
.. _static_transform_publisher: http://wiki.ros.org/tf#static_transform_publisher
.. _cartographer_ros_msgs/FinishTrajectory: https://github.com/cartographer-project/cartographer_ros/blob/master/cartographer_ros_msgs/srv/FinishTrajectory.srv
Expand Down