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

Add option to continuously transform visuals in odometry plugin #1686

Open
wants to merge 3 commits into
base: noetic-devel
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
1 change: 1 addition & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -137,6 +137,7 @@ find_package(catkin REQUIRED
std_srvs
tf2_ros
tf2_geometry_msgs
tf2_eigen
urdf
visualization_msgs
)
Expand Down
1 change: 1 addition & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,7 @@
<depend>std_srvs</depend>
<depend>tf2_ros</depend>
<depend>tf2_geometry_msgs</depend>
<depend>tf2_eigen</depend>
<depend>tinyxml2</depend>
<depend>urdf</depend>
<depend>visualization_msgs</depend>
Expand Down
87 changes: 67 additions & 20 deletions src/rviz/default_plugin/odometry_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,12 +27,15 @@
* POSSIBILITY OF SUCH DAMAGE.
*/

#include <tf2_eigen/tf2_eigen.h>

#include <rviz/ogre_helpers/arrow.h>
#include <rviz/ogre_helpers/axes.h>
#include <rviz/properties/enum_property.h>
#include <rviz/properties/color_property.h>
#include <rviz/properties/float_property.h>
#include <rviz/properties/int_property.h>
#include <rviz/properties/bool_property.h>
#include <rviz/validate_floats.h>
#include <rviz/validate_quaternions.h>

Expand All @@ -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.",
Expand Down Expand Up @@ -153,6 +162,10 @@ void OdometryDisplay::clear()
{
last_used_message_.reset();
}
if (ref_pose_)
{
ref_pose_.reset();
}
}

void OdometryDisplay::updateColorAndAlpha()
Expand Down Expand Up @@ -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;
Expand All @@ -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(),
Expand Down Expand Up @@ -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()
Expand Down
4 changes: 4 additions & 0 deletions src/rviz/default_plugin/odometry_display.h
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,7 @@ class ColorProperty;
class FloatProperty;
class IntProperty;
class EnumProperty;
class BoolProperty;

class CovarianceProperty;

Expand Down Expand Up @@ -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_;

Expand Down
96 changes: 96 additions & 0 deletions src/test/odometry.py
Original file line number Diff line number Diff line change
@@ -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()
Loading