diff --git a/CMakeLists.txt b/CMakeLists.txt index 038a43136c..0088cc8008 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -137,6 +137,7 @@ find_package(catkin REQUIRED std_srvs tf2_ros tf2_geometry_msgs + tf2_eigen urdf visualization_msgs ) diff --git a/package.xml b/package.xml index 94d18b721a..792ee0b438 100644 --- a/package.xml +++ b/package.xml @@ -53,6 +53,7 @@ std_srvs tf2_ros tf2_geometry_msgs + tf2_eigen tinyxml2 urdf visualization_msgs diff --git a/src/rviz/default_plugin/odometry_display.cpp b/src/rviz/default_plugin/odometry_display.cpp index 6fb6fac3e9..f339326b2f 100644 --- a/src/rviz/default_plugin/odometry_display.cpp +++ b/src/rviz/default_plugin/odometry_display.cpp @@ -27,12 +27,15 @@ * POSSIBILITY OF SUCH DAMAGE. */ +#include + #include #include #include #include #include #include +#include #include #include @@ -47,6 +50,12 @@ namespace rviz { OdometryDisplay::OdometryDisplay() { + continuous_transform_property_ = + new BoolProperty("Continuous Transform", false, + "Retransform into fixed frame every timestep. This is particularly useful for " + "messages whose frame moves w.r.t. fixed frame.", + this); + position_tolerance_property_ = new FloatProperty("Position Tolerance", .1, "Distance, in meters from the last arrow dropped, " "that will cause a new arrow to drop.", @@ -153,6 +162,10 @@ void OdometryDisplay::clear() { last_used_message_.reset(); } + if (ref_pose_) + { + ref_pose_.reset(); + } } void OdometryDisplay::updateColorAndAlpha() @@ -278,21 +291,16 @@ void OdometryDisplay::processMessage(const nav_msgs::Odometry::ConstPtr& message if (last_used_message_) { - Ogre::Vector3 last_position(last_used_message_->pose.pose.position.x, - last_used_message_->pose.pose.position.y, - last_used_message_->pose.pose.position.z); - Ogre::Vector3 current_position(message->pose.pose.position.x, message->pose.pose.position.y, - message->pose.pose.position.z); - Eigen::Quaternionf last_orientation(last_used_message_->pose.pose.orientation.w, - last_used_message_->pose.pose.orientation.x, - last_used_message_->pose.pose.orientation.y, - last_used_message_->pose.pose.orientation.z); - Eigen::Quaternionf current_orientation(message->pose.pose.orientation.w, - message->pose.pose.orientation.x, - message->pose.pose.orientation.y, - message->pose.pose.orientation.z); - - if ((last_position - current_position).length() < position_tolerance_property_->getFloat() && + // use double precision in case the positions are very large, like for example with UTM coords + Eigen::Vector3d last_position, current_position; + Eigen::Quaterniond last_orientation, current_orientation; + + tf2::fromMsg(message->pose.pose.position, current_position); + tf2::fromMsg(message->pose.pose.orientation, current_orientation); + tf2::fromMsg(last_used_message_->pose.pose.position, last_position); + tf2::fromMsg(last_used_message_->pose.pose.orientation, last_orientation); + + if ((last_position - current_position).norm() < position_tolerance_property_->getFloat() && last_orientation.angularDistance(current_orientation) < angle_tolerance_property_->getFloat()) { return; @@ -301,14 +309,37 @@ void OdometryDisplay::processMessage(const nav_msgs::Odometry::ConstPtr& message Ogre::Vector3 position; Ogre::Quaternion orientation; - if (!context_->getFrameManager()->transform(message->header, message->pose.pose, position, orientation)) + if (!continuous_transform_property_->getBool()) { - ROS_ERROR("Error transforming odometry '%s' from frame '%s' to frame '%s'", qPrintable(getName()), - message->header.frame_id.c_str(), qPrintable(fixed_frame_)); - return; + if (!context_->getFrameManager()->transform(message->header, message->pose.pose, position, + orientation)) + { + ROS_ERROR("Error transforming odometry '%s' from frame '%s' to frame '%s'", qPrintable(getName()), + message->header.frame_id.c_str(), qPrintable(fixed_frame_)); + return; + } + + // If we arrive here, we're good. Continue... } + else + { + // put the visuals at the pose specified by the message and transform their scene node continuously - // If we arrive here, we're good. Continue... + // Use ref pose for very large transforms where float (default in OGRE) has not enough precision. + // Such large transforms can occur when converting GPS coordinates to a euclidean coordinate system, + // e.g. UTM. The ref pose is set to the position of the first incoming odometry message and is axis + // aligned to the parent frame of the odometry message. + if (!ref_pose_) + { + ref_pose_.reset(new geometry_msgs::Pose()); + ref_pose_->position = message->pose.pose.position; + } + + const geometry_msgs::Pose& p = message->pose.pose; + position = Ogre::Vector3(p.position.x - ref_pose_->position.x, p.position.y - ref_pose_->position.y, + p.position.z - ref_pose_->position.z); + orientation = Ogre::Quaternion(p.orientation.w, p.orientation.x, p.orientation.y, p.orientation.z); + } // Create a scene node, and attach the arrow and the covariance to it Axes* axes = new Axes(scene_manager_, scene_node_, axes_length_property_->getFloat(), @@ -372,6 +403,22 @@ void OdometryDisplay::update(float /*wall_dt*/, float /*ros_dt*/) assert(arrows_.size() == axes_.size()); assert(axes_.size() == covariance_property_->sizeVisual()); + + // continuously set the scene node's position to ref pose + if (!continuous_transform_property_->getBool() || !last_used_message_ || !ref_pose_) + return; + + Ogre::Vector3 position; + Ogre::Quaternion orientation; + if (!context_->getFrameManager()->transform(last_used_message_->header.frame_id, ros::Time(), + *ref_pose_, position, orientation)) + { + // the error output with setStatus is already generated by MessageFilterDisplay + return; + } + + scene_node_->setPosition(position); + scene_node_->setOrientation(orientation); } void OdometryDisplay::reset() diff --git a/src/rviz/default_plugin/odometry_display.h b/src/rviz/default_plugin/odometry_display.h index e1bf86f98f..731b2130af 100644 --- a/src/rviz/default_plugin/odometry_display.h +++ b/src/rviz/default_plugin/odometry_display.h @@ -51,6 +51,7 @@ class ColorProperty; class FloatProperty; class IntProperty; class EnumProperty; +class BoolProperty; class CovarianceProperty; @@ -102,6 +103,9 @@ private Q_SLOTS: D_Axes axes_; nav_msgs::Odometry::ConstPtr last_used_message_; + geometry_msgs::Pose::Ptr ref_pose_; + + rviz::BoolProperty* continuous_transform_property_; rviz::EnumProperty* shape_property_; diff --git a/src/test/odometry.py b/src/test/odometry.py new file mode 100644 index 0000000000..04ec0d4758 --- /dev/null +++ b/src/test/odometry.py @@ -0,0 +1,96 @@ +#!/usr/bin/env python + +import math +import time + +import rospy +from geometry_msgs.msg import TransformStamped +from visualization_msgs.msg import Marker +from nav_msgs.msg import Odometry +from tf.transformations import quaternion_from_euler +from tf2_ros.transform_broadcaster import TransformBroadcaster + +RATE = 30 + + +def odom_to_tf(odom_msg): + tf = TransformStamped() + tf.header = odom_msg.header + tf.child_frame_id = odom_msg.child_frame_id + tf.transform.translation = odom_msg.pose.pose.position + tf.transform.rotation = odom_msg.pose.pose.orientation + tf_broadcaster.sendTransform(tf) + + +def draw_eight(elapsed_time, full_cycle_duration=10, scale=10): + # lemniscate of Gerono + progress = (elapsed_time % full_cycle_duration) / full_cycle_duration + t = -0.5 * math.pi + progress * (2 * math.pi) + x = math.cos(t) * scale + y = math.sin(t) * math.cos(t) * scale + dx_dt = -math.sin(t) + dy_dt = math.cos(t) * math.cos(t) - math.sin(t) * math.sin(t) + yaw = math.atan2(dy_dt, dx_dt) + return x, y, yaw + + +def display_dummy_robot(stamp): + marker = Marker() + marker.header.frame_id = "base_link" + marker.header.stamp = stamp + marker.ns = "robot" + marker.id = 0 + marker.type = Marker.CUBE + marker.action = Marker.ADD + marker.pose.position.x = 0 + marker.pose.position.y = 0 + marker.pose.position.z = 0 + marker.pose.orientation.x = 0.0 + marker.pose.orientation.y = 0.0 + marker.pose.orientation.z = 0.0 + marker.pose.orientation.w = 1.0 + marker.scale.x = 1 + marker.scale.y = 1 + marker.scale.z = 1 + marker.color.a = 1.0 + marker.color.r = 0.0 + marker.color.g = 1.0 + marker.color.b = 0.0 + vis_pub.publish(marker) + + +rospy.init_node("odometry_test", anonymous=True) + +tf_broadcaster = TransformBroadcaster() + +odom_pub = rospy.Publisher("robot/odom", Odometry, queue_size=5) +vis_pub = rospy.Publisher("robot/marker", Marker, queue_size=5) + +time.sleep(1) + +rate = rospy.Rate(RATE) +start = rospy.Time.now() +while not rospy.is_shutdown(): + now = rospy.Time.now() + + robot_x, robot_y, robot_yaw = draw_eight((now - start).to_sec()) + q = quaternion_from_euler(0, 0, robot_yaw) + + odom_robot = Odometry() + odom_robot.header.stamp = now + odom_robot.header.frame_id = "world" + odom_robot.child_frame_id = "base_link" + odom_robot.pose.pose.position.x = robot_x + odom_robot.pose.pose.position.y = robot_y + odom_robot.pose.pose.orientation.x = q[0] + odom_robot.pose.pose.orientation.y = q[1] + odom_robot.pose.pose.orientation.z = q[2] + odom_robot.pose.pose.orientation.w = q[3] + + odom_to_tf(odom_robot) + + odom_pub.publish(odom_robot) + + display_dummy_robot(now) + + rate.sleep() diff --git a/src/test/odometry.rviz b/src/test/odometry.rviz new file mode 100755 index 0000000000..9691a59af4 --- /dev/null +++ b/src/test/odometry.rviz @@ -0,0 +1,165 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + - /Odometry1 + - /Odometry1/Shape1 + Splitter Ratio: 0.6264705657958984 + Tree Height: 818 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Angle Tolerance: 0.5 + Class: rviz/Odometry + Covariance: + Orientation: + Alpha: 0.5 + Color: 255; 255; 127 + Color Style: Unique + Frame: Local + Offset: 1 + Scale: 1 + Value: true + Position: + Alpha: 0.30000001192092896 + Color: 204; 51; 204 + Scale: 1 + Value: true + Value: true + Enabled: true + Keep: 52 + Name: Odometry + Position Tolerance: 1 + Queue Size: 10 + Shape: + Alpha: 1 + Axes Length: 1 + Axes Radius: 0.10000000149011612 + Color: 255; 25; 0 + Head Length: 0.30000001192092896 + Head Radius: 0.10000000149011612 + Shaft Length: 0.20000000298023224 + Shaft Radius: 0.05000000074505806 + Value: Arrow + Topic: /robot/odom + Unreliable: false + Value: true + - Class: rviz/Marker + Enabled: true + Marker Topic: /robot/marker + Name: Marker + Namespaces: + robot: true + Queue Size: 100 + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: world + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 20.20941925048828 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Field of View: 0.7853981852531433 + Focal Point: + X: 1.479522943496704 + Y: 0.4954601228237152 + Z: -1.4441502094268799 + Focal Shape Fixed Size: false + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.7553982138633728 + Target Frame: + Yaw: 0.8353981971740723 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1115 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd000000040000000000000156000003bdfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000003bd000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000003bdfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000003bd000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007760000003efc0100000002fb0000000800540069006d00650100000000000007760000025600fffffffb0000000800540069006d0065010000000000000450000000000000000000000505000003bd00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1910 + X: 0 + Y: 25