diff --git a/MIGRATION.md b/MIGRATION.md index 731035f..8a0a59f 100644 --- a/MIGRATION.md +++ b/MIGRATION.md @@ -4,5 +4,5 @@ API changes in Rviz Visual Tools releases ## ROS Melodic +- Affine3d no longer used, replaced by more computationally efficient Isometry3d. Simple find-replace should suffice - RvizVisualTools::publishMarkers called ros::spinOnce() in previous versions. This was usually a bug as it might lead to running ROS callback functions in unrelated threads (e.g. your UI thread). In the unlikely case that your program relied on publishMarkers calling ros::spinOnce() you will now have to add either a ros::spinOnce after your call to publishMarkers or simply add a ros::AsyncSpinner. See http://wiki.ros.org/roscpp/Overview/Callbacks%20and%20Spinning for more details. - diff --git a/README.md b/README.md index 52c5171..e181ffa 100644 --- a/README.md +++ b/README.md @@ -93,7 +93,7 @@ Start rviz and create a new marker using the 'Add' button at the bottom right. C In the following snippet we create a pose at xyz (0.1, 0.1, 0.1) and rotate the pose down 45 degrees along the Y axis. Then we publish the pose as a arrow for visualziation in Rviz. Make sure your Rviz fixed frame is the same as the one chosen in the code. // Create pose - Eigen::Affine3d pose; + Eigen::Isometry3d pose; pose = Eigen::AngleAxisd(M_PI/4, Eigen::Vector3d::UnitY()); // rotate along X axis by 45 degrees pose.translation() = Eigen::Vector3d( 0.1, 0.1, 0.1 ); // translate x,y,z @@ -257,7 +257,7 @@ This class quickly gives you basic 6dof pose interactive marker funcitonality. A This tool lets you easily debug Eigen transforms in Rviz. Demo use: rviz_visual_tools::TFVisualTools tf_visualizer; - Eigen::Affine3d world_to_shelf_transform = Eigen::Affine3d::Identity(); // or whatever value + Eigen::Isometry3d world_to_shelf_transform = Eigen::Isometry3d::Identity(); // or whatever value tf_visualizer.publishTransform(world_to_shelf_transform, "world", "shelf"); *Note: this is a work in progress* diff --git a/include/rviz_visual_tools/imarker_simple.h b/include/rviz_visual_tools/imarker_simple.h index 94616e2..943b0c0 100644 --- a/include/rviz_visual_tools/imarker_simple.h +++ b/include/rviz_visual_tools/imarker_simple.h @@ -78,7 +78,7 @@ class IMarkerSimple geometry_msgs::Pose& getPose(); - void setPose(const Eigen::Affine3d& pose); + void setPose(const Eigen::Isometry3d& pose); void setPose(const geometry_msgs::Pose& pose); diff --git a/include/rviz_visual_tools/rviz_visual_tools.h b/include/rviz_visual_tools/rviz_visual_tools.h index 8973cb6..01c0dd7 100644 --- a/include/rviz_visual_tools/rviz_visual_tools.h +++ b/include/rviz_visual_tools/rviz_visual_tools.h @@ -305,7 +305,7 @@ class RvizVisualTools * \param point b - x,y,z in space of a point * \return vector from a to b */ - Eigen::Affine3d getVectorBetweenPoints(const Eigen::Vector3d& a, const Eigen::Vector3d& b) const; + Eigen::Isometry3d getVectorBetweenPoints(const Eigen::Vector3d& a, const Eigen::Vector3d& b) const; /** * \brief Find the center between to points @@ -397,7 +397,7 @@ a * Warning: when using this in a loop be sure to call trigger() at end * \param scale - size of the cone * \return true on success */ - bool publishCone(const Eigen::Affine3d& pose, double angle, colors color = TRANSLUCENT, double scale = 1.0); + bool publishCone(const Eigen::Isometry3d& pose, double angle, colors color = TRANSLUCENT, double scale = 1.0); bool publishCone(const geometry_msgs::Pose& pose, double angle, colors color = TRANSLUCENT, double scale = 1.0); /** @@ -407,7 +407,7 @@ a * Warning: when using this in a loop be sure to call trigger() at end * \param scale - the size of the vizualized plane * \return true on success */ - bool publishXYPlane(const Eigen::Affine3d& pose, colors color = TRANSLUCENT, double scale = 1.0); + bool publishXYPlane(const Eigen::Isometry3d& pose, colors color = TRANSLUCENT, double scale = 1.0); bool publishXYPlane(const geometry_msgs::Pose& pose, colors color = TRANSLUCENT, double scale = 1.0); /** @@ -417,7 +417,7 @@ a * Warning: when using this in a loop be sure to call trigger() at end * \param scale - the size of the vizualized plane * \return true on success */ - bool publishXZPlane(const Eigen::Affine3d& pose, colors color = TRANSLUCENT, double scale = 1.0); + bool publishXZPlane(const Eigen::Isometry3d& pose, colors color = TRANSLUCENT, double scale = 1.0); bool publishXZPlane(const geometry_msgs::Pose& pose, colors color = TRANSLUCENT, double scale = 1.0); /** @@ -427,7 +427,7 @@ a * Warning: when using this in a loop be sure to call trigger() at end * \param scale - the size of the vizualized plane * \return true on success */ - bool publishYZPlane(const Eigen::Affine3d& pose, colors color = TRANSLUCENT, double scale = 1.0); + bool publishYZPlane(const Eigen::Isometry3d& pose, colors color = TRANSLUCENT, double scale = 1.0); bool publishYZPlane(const geometry_msgs::Pose& pose, colors color = TRANSLUCENT, double scale = 1.0); /** @@ -440,7 +440,7 @@ a * Warning: when using this in a loop be sure to call trigger() at end * to incremental counter * \return true on success */ - bool publishSphere(const Eigen::Affine3d& pose, colors color = BLUE, scales scale = MEDIUM, + bool publishSphere(const Eigen::Isometry3d& pose, colors color = BLUE, scales scale = MEDIUM, const std::string& ns = "Sphere", std::size_t id = 0); bool publishSphere(const Eigen::Vector3d& point, colors color = BLUE, scales scale = MEDIUM, const std::string& ns = "Sphere", std::size_t id = 0); @@ -456,7 +456,7 @@ a * Warning: when using this in a loop be sure to call trigger() at end const std::string& ns = "Sphere", std::size_t id = 0); bool publishSphere(const geometry_msgs::Pose& pose, const std_msgs::ColorRGBA& color, const geometry_msgs::Vector3 scale, const std::string& ns = "Sphere", std::size_t id = 0); - bool publishSphere(const Eigen::Affine3d& pose, const std_msgs::ColorRGBA& color, const geometry_msgs::Vector3 scale, + bool publishSphere(const Eigen::Isometry3d& pose, const std_msgs::ColorRGBA& color, const geometry_msgs::Vector3 scale, const std::string& ns = "Sphere", std::size_t id = 0); bool publishSphere(const Eigen::Vector3d& point, const std_msgs::ColorRGBA& color, const geometry_msgs::Vector3 scale, const std::string& ns = "Sphere", std::size_t id = 0); @@ -503,7 +503,7 @@ a * Warning: when using this in a loop be sure to call trigger() at end * \param length - the length of the arrow tail, if zero, will auto set with scale * \return true on success */ - bool publishXArrow(const Eigen::Affine3d& pose, colors color = RED, scales scale = MEDIUM, double length = 0.0); + bool publishXArrow(const Eigen::Isometry3d& pose, colors color = RED, scales scale = MEDIUM, double length = 0.0); bool publishXArrow(const geometry_msgs::Pose& pose, colors color = RED, scales scale = MEDIUM, double length = 0.0); bool publishXArrow(const geometry_msgs::PoseStamped& pose, colors color = RED, scales scale = MEDIUM, double length = 0.0); @@ -516,7 +516,7 @@ a * Warning: when using this in a loop be sure to call trigger() at end * \param length - the length of the arrow tail, if zero, will auto set with scale * \return true on success */ - bool publishYArrow(const Eigen::Affine3d& pose, colors color = GREEN, scales scale = MEDIUM, double length = 0.0); + bool publishYArrow(const Eigen::Isometry3d& pose, colors color = GREEN, scales scale = MEDIUM, double length = 0.0); bool publishYArrow(const geometry_msgs::Pose& pose, colors color = GREEN, scales scale = MEDIUM, double length = 0.0); bool publishYArrow(const geometry_msgs::PoseStamped& pose, colors color = GREEN, scales scale = MEDIUM, double length = 0.0); @@ -529,7 +529,7 @@ a * Warning: when using this in a loop be sure to call trigger() at end * \param length - the length of the arrow tail, if zero, will auto set with scale * \return true on success */ - bool publishZArrow(const Eigen::Affine3d& pose, colors color = BLUE, scales scale = MEDIUM, double length = 0.0, + bool publishZArrow(const Eigen::Isometry3d& pose, colors color = BLUE, scales scale = MEDIUM, double length = 0.0, std::size_t id = 0); bool publishZArrow(const geometry_msgs::Pose& pose, colors color = BLUE, scales scale = MEDIUM, double length = 0.0); bool publishZArrow(const geometry_msgs::PoseStamped& pose, colors color = BLUE, scales scale = MEDIUM, @@ -547,7 +547,7 @@ a * Warning: when using this in a loop be sure to call trigger() at end * \param end - the ending point of the arrow * \return true on success */ - bool publishArrow(const Eigen::Affine3d& pose, colors color = BLUE, scales scale = MEDIUM, double length = 0.0, + bool publishArrow(const Eigen::Isometry3d& pose, colors color = BLUE, scales scale = MEDIUM, double length = 0.0, std::size_t id = 0); bool publishArrow(const geometry_msgs::Pose& pose, colors color = BLUE, scales scale = MEDIUM, double length = 0.0, std::size_t id = 0); @@ -577,7 +577,7 @@ a * Warning: when using this in a loop be sure to call trigger() at end * \return true on success */ bool publishCuboid(const geometry_msgs::Pose& pose, double depth, double width, double height, colors color = BLUE); - bool publishCuboid(const Eigen::Affine3d& pose, double depth, double width, double height, colors color = BLUE); + bool publishCuboid(const Eigen::Isometry3d& pose, double depth, double width, double height, colors color = BLUE); /** * \brief Display a marker of line @@ -587,7 +587,7 @@ a * Warning: when using this in a loop be sure to call trigger() at end * \param scale - an enum pre-defined name of a size * \return true on success */ - bool publishLine(const Eigen::Affine3d& point1, const Eigen::Affine3d& point2, colors color = BLUE, + bool publishLine(const Eigen::Isometry3d& point1, const Eigen::Isometry3d& point2, colors color = BLUE, scales scale = MEDIUM); bool publishLine(const Eigen::Vector3d& point1, const Eigen::Vector3d& point2, colors color = BLUE, scales scale = MEDIUM); @@ -639,7 +639,7 @@ a * Warning: when using this in a loop be sure to call trigger() at end const std::string& ns = "Path"); bool publishPath(const std::vector& path, colors color = RED, scales scale = MEDIUM, const std::string& ns = "Path"); - bool publishPath(const EigenSTL::vector_Affine3d& path, colors color = RED, scales scale = MEDIUM, + bool publishPath(const EigenSTL::vector_Isometry3d& path, colors color = RED, scales scale = MEDIUM, const std::string& ns = "Path"); bool publishPath(const EigenSTL::vector_Vector3d& path, colors color = RED, scales scale = MEDIUM, const std::string& ns = "Path"); @@ -647,7 +647,7 @@ a * Warning: when using this in a loop be sure to call trigger() at end const std::string& ns = "Path"); bool publishPath(const EigenSTL::vector_Vector3d& path, colors color = RED, double radius = 0.01, const std::string& ns = "Path"); - bool publishPath(const EigenSTL::vector_Affine3d& path, colors color = RED, double radius = 0.01, + bool publishPath(const EigenSTL::vector_Isometry3d& path, colors color = RED, double radius = 0.01, const std::string& ns = "Path"); /** @@ -688,7 +688,7 @@ a * Warning: when using this in a loop be sure to call trigger() at end * to incremental counter * \return true on success */ - bool publishWireframeCuboid(const Eigen::Affine3d& pose, double depth, double width, double height, + bool publishWireframeCuboid(const Eigen::Isometry3d& pose, double depth, double width, double height, colors color = BLUE, const std::string& ns = "Wireframe Cuboid", std::size_t id = 0); /** @@ -701,7 +701,7 @@ a * Warning: when using this in a loop be sure to call trigger() at end * \param id - unique counter that allows you to overwrite a previous marker. if 0, defaults to incremental counter * \return true on success */ - bool publishWireframeCuboid(const Eigen::Affine3d& pose, const Eigen::Vector3d& min_point, + bool publishWireframeCuboid(const Eigen::Isometry3d& pose, const Eigen::Vector3d& min_point, const Eigen::Vector3d& max_point, colors color = BLUE, const std::string& ns = "Wireframe Cuboid", std::size_t id = 0); @@ -714,9 +714,9 @@ a * Warning: when using this in a loop be sure to call trigger() at end * \param id - unique counter that allows you to overwrite a previous marker. if 0, defaults to incremental counter * \return true on success */ - bool publishWireframeRectangle(const Eigen::Affine3d& pose, double height, double width, colors color = BLUE, + bool publishWireframeRectangle(const Eigen::Isometry3d& pose, double height, double width, colors color = BLUE, scales scale = MEDIUM, std::size_t id = 0); - bool publishWireframeRectangle(const Eigen::Affine3d& pose, const Eigen::Vector3d& p1_in, + bool publishWireframeRectangle(const Eigen::Isometry3d& pose, const Eigen::Vector3d& p1_in, const Eigen::Vector3d& p2_in, const Eigen::Vector3d& p3_in, const Eigen::Vector3d& p4_in, colors color, scales scale); /** @@ -727,7 +727,7 @@ a * Warning: when using this in a loop be sure to call trigger() at end * \param color - an enum pre-defined name of a color * \return true on success */ - bool publishAxisLabeled(const Eigen::Affine3d& pose, const std::string& label, scales scale = MEDIUM, + bool publishAxisLabeled(const Eigen::Isometry3d& pose, const std::string& label, scales scale = MEDIUM, colors color = WHITE); bool publishAxisLabeled(const geometry_msgs::Pose& pose, const std::string& label, scales scale = MEDIUM, colors color = WHITE); @@ -742,10 +742,10 @@ a * Warning: when using this in a loop be sure to call trigger() at end * \return true on success */ bool publishAxis(const geometry_msgs::Pose& pose, scales scale = MEDIUM, const std::string& ns = "Axis"); - bool publishAxis(const Eigen::Affine3d& pose, scales scale = MEDIUM, const std::string& ns = "Axis"); + bool publishAxis(const Eigen::Isometry3d& pose, scales scale = MEDIUM, const std::string& ns = "Axis"); bool publishAxis(const geometry_msgs::Pose& pose, double length, double radius = 0.01, const std::string& ns = "Axis"); - bool publishAxis(const Eigen::Affine3d& pose, double length, double radius = 0.01, const std::string& ns = "Axis"); + bool publishAxis(const Eigen::Isometry3d& pose, double length, double radius = 0.01, const std::string& ns = "Axis"); private: /** @@ -756,7 +756,7 @@ a * Warning: when using this in a loop be sure to call trigger() at end * \param ns - namespace * \return true on success */ - bool publishAxisInternal(const Eigen::Affine3d& pose, double length = 0.1, double radius = 0.01, + bool publishAxisInternal(const Eigen::Isometry3d& pose, double length = 0.1, double radius = 0.01, const std::string& ns = "Axis"); public: @@ -768,9 +768,9 @@ a * Warning: when using this in a loop be sure to call trigger() at end * \param ns - namespace * \return true on success */ - bool publishAxisPath(const EigenSTL::vector_Affine3d& path, scales scale = MEDIUM, + bool publishAxisPath(const EigenSTL::vector_Isometry3d& path, scales scale = MEDIUM, const std::string& ns = "Axis Path"); - bool publishAxisPath(const EigenSTL::vector_Affine3d& path, double length = 0.1, double radius = 0.01, + bool publishAxisPath(const EigenSTL::vector_Isometry3d& path, double length = 0.1, double radius = 0.01, const std::string& ns = "Axis Path"); /** @@ -796,7 +796,7 @@ a * Warning: when using this in a loop be sure to call trigger() at end * \param radius - geometry of cylinder * \return true on success */ - bool publishCylinder(const Eigen::Affine3d& pose, colors color = BLUE, double height = 0.1, double radius = 0.01, + bool publishCylinder(const Eigen::Isometry3d& pose, colors color = BLUE, double height = 0.1, double radius = 0.01, const std::string& ns = "Cylinder"); bool publishCylinder(const geometry_msgs::Pose& pose, colors color = BLUE, double height = 0.1, double radius = 0.01, const std::string& ns = "Cylinder"); @@ -814,7 +814,7 @@ a * Warning: when using this in a loop be sure to call trigger() at end * to incremental counter * \return true on success */ - bool publishMesh(const Eigen::Affine3d& pose, const std::string& file_name, colors color = CLEAR, double scale = 1, + bool publishMesh(const Eigen::Isometry3d& pose, const std::string& file_name, colors color = CLEAR, double scale = 1, const std::string& ns = "mesh", std::size_t id = 0); bool publishMesh(const geometry_msgs::Pose& pose, const std::string& file_name, colors color = CLEAR, double scale = 1, const std::string& ns = "mesh", std::size_t id = 0); @@ -837,9 +837,9 @@ a * Warning: when using this in a loop be sure to call trigger() at end * \param static_id - if true, only one text can be published at a time * \return true on success */ - bool publishText(const Eigen::Affine3d& pose, const std::string& text, colors color = WHITE, scales scale = MEDIUM, + bool publishText(const Eigen::Isometry3d& pose, const std::string& text, colors color = WHITE, scales scale = MEDIUM, bool static_id = true); - bool publishText(const Eigen::Affine3d& pose, const std::string& text, colors color, + bool publishText(const Eigen::Isometry3d& pose, const std::string& text, colors color, const geometry_msgs::Vector3 scale, bool static_id = true); bool publishText(const geometry_msgs::Pose& pose, const std::string& text, colors color = WHITE, scales scale = MEDIUM, bool static_id = true); @@ -851,14 +851,14 @@ a * Warning: when using this in a loop be sure to call trigger() at end * \param pose * \return converted pose */ - static geometry_msgs::Pose convertPose(const Eigen::Affine3d& pose); + static geometry_msgs::Pose convertPose(const Eigen::Isometry3d& pose); /** * \brief Convert an Eigen pose to a geometry_msg pose - thread safe * \param Eigen pose - input * \param ROS msg pose - output */ - static void convertPoseSafe(const Eigen::Affine3d& pose, geometry_msgs::Pose& pose_msg); + static void convertPoseSafe(const Eigen::Isometry3d& pose, geometry_msgs::Pose& pose_msg); /** * \brief Convert a geometry_msg pose to an Eigen pose @@ -866,14 +866,14 @@ a * Warning: when using this in a loop be sure to call trigger() at end * \param ROS msg pose * \return converted pose */ - static Eigen::Affine3d convertPose(const geometry_msgs::Pose& pose); + static Eigen::Isometry3d convertPose(const geometry_msgs::Pose& pose); /** * \brief Convert a geometry_msg pose to an Eigen pose - thread safe * \param ROS msg pose - input * \param Eigen pose - output */ - static void convertPoseSafe(const geometry_msgs::Pose& pose_msg, Eigen::Affine3d& pose); + static void convertPoseSafe(const geometry_msgs::Pose& pose_msg, Eigen::Isometry3d& pose); /** * \brief Convert a geometry_msg point (32bit) to an Eigen pose @@ -881,13 +881,13 @@ a * Warning: when using this in a loop be sure to call trigger() at end * \param pose * \return converted point with default rotation matrix */ - static Eigen::Affine3d convertPoint32ToPose(const geometry_msgs::Point32& point); + static Eigen::Isometry3d convertPoint32ToPose(const geometry_msgs::Point32& point); /** * \brief Add an identity rotation matrix to make a point have a full pose */ static geometry_msgs::Pose convertPointToPose(const geometry_msgs::Point& point); - static Eigen::Affine3d convertPointToPose(const Eigen::Vector3d& point); + static Eigen::Isometry3d convertPointToPose(const Eigen::Vector3d& point); /** * \brief Convert an Eigen pose to a geometry_msg point @@ -895,7 +895,7 @@ a * Warning: when using this in a loop be sure to call trigger() at end * \param pose * \return converted point with orientation discarded */ - static geometry_msgs::Point convertPoseToPoint(const Eigen::Affine3d& pose); + static geometry_msgs::Point convertPoseToPoint(const Eigen::Isometry3d& pose); /** * \brief Convert a geometry_msg point to an Eigen point @@ -947,9 +947,9 @@ a * Warning: when using this in a loop be sure to call trigger() at end @param rx, ry, rz - rotations about x, y, z, respectively @param convention - default is rviz_visual_tools::XYZ */ - static Eigen::Affine3d convertFromXYZRPY(double tx, double ty, double tz, double rx, double ry, double rz, + static Eigen::Isometry3d convertFromXYZRPY(double tx, double ty, double tz, double rx, double ry, double rz, EulerConvention convention); // ZYX is ROS standard - static Eigen::Affine3d convertFromXYZRPY(const std::vector& transform6, + static Eigen::Isometry3d convertFromXYZRPY(const std::vector& transform6, EulerConvention convention); // ZYX is ROS standard // TODO(davetcoleman): add opposite conversion that uses Eigen::Vector3d rpy = pose.rotation().eulerAngles(0, 1, 2); @@ -960,8 +960,8 @@ a * Warning: when using this in a loop be sure to call trigger() at end * \param input Eigen pose * \param output vector of size 6 in order xyz rpy */ - static void convertToXYZRPY(const Eigen::Affine3d& pose, std::vector& xyzrpy); - static void convertToXYZRPY(const Eigen::Affine3d& pose, double& x, double& y, double& z, double& roll, double& pitch, + static void convertToXYZRPY(const Eigen::Isometry3d& pose, std::vector& xyzrpy); + static void convertToXYZRPY(const Eigen::Isometry3d& pose, double& x, double& y, double& z, double& roll, double& pitch, double& yaw); /** * \brief Create a random pose within bounds of random_pose_bounds_ @@ -969,7 +969,7 @@ a * Warning: when using this in a loop be sure to call trigger() at end * \parma options bounds on the pose to generate */ static void generateRandomPose(geometry_msgs::Pose& pose, RandomPoseBounds pose_bounds = RandomPoseBounds()); - static void generateRandomPose(Eigen::Affine3d& pose, RandomPoseBounds pose_bounds = RandomPoseBounds()); + static void generateRandomPose(Eigen::Isometry3d& pose, RandomPoseBounds pose_bounds = RandomPoseBounds()); /** * \brief Create a random rectangular cuboid of some shape @@ -991,7 +991,7 @@ a * Warning: when using this in a loop be sure to call trigger() at end * \param threshold - how close in value they must be in order to be considered the same * \return true if equal */ - static bool posesEqual(const Eigen::Affine3d& pose1, const Eigen::Affine3d& pose2, double threshold = 0.000001); + static bool posesEqual(const Eigen::Isometry3d& pose1, const Eigen::Isometry3d& pose2, double threshold = 0.000001); /** * \brief Get random between min and max @@ -1008,17 +1008,17 @@ a * Warning: when using this in a loop be sure to call trigger() at end /** * \brief Display in the console a transform in quaternions */ - static void printTransform(const Eigen::Affine3d& transform); + static void printTransform(const Eigen::Isometry3d& transform); /** * \brief Display in the console a transform in roll pitch yaw */ - static void printTransformRPY(const Eigen::Affine3d& transform); + static void printTransformRPY(const Eigen::Isometry3d& transform); /** * \brief Display in the console a transform with full 3x3 rotation matrix */ - static void printTransformFull(const Eigen::Affine3d& transform); + static void printTransformFull(const Eigen::Isometry3d& transform); /** \brief Getter for PsychedelicMode */ bool getPsychedelicMode() const diff --git a/include/rviz_visual_tools/tf_visual_tools.h b/include/rviz_visual_tools/tf_visual_tools.h index 1845399..3671f81 100644 --- a/include/rviz_visual_tools/tf_visual_tools.h +++ b/include/rviz_visual_tools/tf_visual_tools.h @@ -74,7 +74,7 @@ class TFVisualTools * \brief Visualize transforms in Rviz, etc * \return true on success */ - bool publishTransform(const Eigen::Affine3d& transform, const std::string& from_frame, const std::string& to_frame); + bool publishTransform(const Eigen::Isometry3d& transform, const std::string& from_frame, const std::string& to_frame); /** * \brief At a certain frequency update the tf transforms that we are tracking diff --git a/src/imarker_simple.cpp b/src/imarker_simple.cpp index 99b4d07..e4a0d4c 100644 --- a/src/imarker_simple.cpp +++ b/src/imarker_simple.cpp @@ -63,7 +63,7 @@ geometry_msgs::Pose& IMarkerSimple::getPose() return latest_pose_; } -void IMarkerSimple::setPose(const Eigen::Affine3d& pose) +void IMarkerSimple::setPose(const Eigen::Isometry3d& pose) { geometry_msgs::Pose pose_msg; rviz_visual_tools::RvizVisualTools::convertPoseSafe(pose, pose_msg); diff --git a/src/rviz_visual_tools.cpp b/src/rviz_visual_tools.cpp index 46c6617..e217a97 100644 --- a/src/rviz_visual_tools.cpp +++ b/src/rviz_visual_tools.cpp @@ -714,7 +714,7 @@ Eigen::Vector3d RvizVisualTools::getCenterPoint(const Eigen::Vector3d& a, const return center; } -Eigen::Affine3d RvizVisualTools::getVectorBetweenPoints(const Eigen::Vector3d& a, const Eigen::Vector3d& b) const +Eigen::Isometry3d RvizVisualTools::getVectorBetweenPoints(const Eigen::Vector3d& a, const Eigen::Vector3d& b) const { bool verbose = false; @@ -725,7 +725,7 @@ Eigen::Affine3d RvizVisualTools::getVectorBetweenPoints(const Eigen::Vector3d& a // http://answers.ros.org/question/31006/how-can-a-vector3-axis-be-used-to-produce-a-quaternion/ // Solution pose - Eigen::Affine3d result_pose = Eigen::Affine3d::Identity(); + Eigen::Isometry3d result_pose = Eigen::Isometry3d::Identity(); // Goal pose: Eigen::Quaterniond q; @@ -918,7 +918,7 @@ bool RvizVisualTools::publishMarkers(visualization_msgs::MarkerArray& markers) return true; } -bool RvizVisualTools::publishCone(const Eigen::Affine3d& pose, double angle, colors color, double scale) +bool RvizVisualTools::publishCone(const Eigen::Isometry3d& pose, double angle, colors color, double scale) { return publishCone(convertPose(pose), angle, color, scale); } @@ -964,7 +964,7 @@ bool RvizVisualTools::publishCone(const geometry_msgs::Pose& pose, double angle, return publishMarker(triangle_marker_); } -bool RvizVisualTools::publishXYPlane(const Eigen::Affine3d& pose, colors color, double scale) +bool RvizVisualTools::publishXYPlane(const Eigen::Isometry3d& pose, colors color, double scale) { return publishXYPlane(convertPose(pose), color, scale); } @@ -1010,7 +1010,7 @@ bool RvizVisualTools::publishXYPlane(const geometry_msgs::Pose& pose, colors col return publishMarker(triangle_marker_); } -bool RvizVisualTools::publishXZPlane(const Eigen::Affine3d& pose, colors color, double scale) +bool RvizVisualTools::publishXZPlane(const Eigen::Isometry3d& pose, colors color, double scale) { return publishXZPlane(convertPose(pose), color, scale); } @@ -1056,7 +1056,7 @@ bool RvizVisualTools::publishXZPlane(const geometry_msgs::Pose& pose, colors col return publishMarker(triangle_marker_); } -bool RvizVisualTools::publishYZPlane(const Eigen::Affine3d& pose, colors color, double scale) +bool RvizVisualTools::publishYZPlane(const Eigen::Isometry3d& pose, colors color, double scale) { return publishYZPlane(convertPose(pose), color, scale); } @@ -1102,7 +1102,7 @@ bool RvizVisualTools::publishYZPlane(const geometry_msgs::Pose& pose, colors col return publishMarker(triangle_marker_); } -bool RvizVisualTools::publishSphere(const Eigen::Affine3d& pose, colors color, scales scale, const std::string& ns, +bool RvizVisualTools::publishSphere(const Eigen::Isometry3d& pose, colors color, scales scale, const std::string& ns, std::size_t id) { return publishSphere(convertPose(pose), color, scale, ns, id); @@ -1154,7 +1154,7 @@ bool RvizVisualTools::publishSphere(const geometry_msgs::Pose& pose, colors colo return publishSphere(pose, getColor(color), scale, ns, id); } -bool RvizVisualTools::publishSphere(const Eigen::Affine3d& pose, const std_msgs::ColorRGBA& color, +bool RvizVisualTools::publishSphere(const Eigen::Isometry3d& pose, const std_msgs::ColorRGBA& color, const geometry_msgs::Vector3 scale, const std::string& ns, std::size_t id) { return publishSphere(convertPose(pose), color, scale, ns, id); @@ -1220,7 +1220,7 @@ bool RvizVisualTools::publishSphere(const geometry_msgs::PoseStamped& pose, colo return true; } -bool RvizVisualTools::publishXArrow(const Eigen::Affine3d& pose, colors color, scales scale, double length) +bool RvizVisualTools::publishXArrow(const Eigen::Isometry3d& pose, colors color, scales scale, double length) { return publishArrow(convertPose(pose), color, scale, length); } @@ -1235,42 +1235,42 @@ bool RvizVisualTools::publishXArrow(const geometry_msgs::PoseStamped& pose, colo return publishArrow(pose, color, scale, length); } -bool RvizVisualTools::publishYArrow(const Eigen::Affine3d& pose, colors color, scales scale, double length) +bool RvizVisualTools::publishYArrow(const Eigen::Isometry3d& pose, colors color, scales scale, double length) { - Eigen::Affine3d arrow_pose = pose * Eigen::AngleAxisd(M_PI / 2, Eigen::Vector3d::UnitZ()); + Eigen::Isometry3d arrow_pose = pose * Eigen::AngleAxisd(M_PI / 2, Eigen::Vector3d::UnitZ()); return publishArrow(convertPose(arrow_pose), color, scale, length); } bool RvizVisualTools::publishYArrow(const geometry_msgs::Pose& pose, colors color, scales scale, double length) { - Eigen::Affine3d arrow_pose = convertPose(pose) * Eigen::AngleAxisd(M_PI / 2, Eigen::Vector3d::UnitZ()); + Eigen::Isometry3d arrow_pose = convertPose(pose) * Eigen::AngleAxisd(M_PI / 2, Eigen::Vector3d::UnitZ()); return publishArrow(convertPose(arrow_pose), color, scale, length); } bool RvizVisualTools::publishYArrow(const geometry_msgs::PoseStamped& pose, colors color, scales scale, double length) { - Eigen::Affine3d arrow_pose = convertPose(pose.pose) * Eigen::AngleAxisd(M_PI / 2, Eigen::Vector3d::UnitZ()); + Eigen::Isometry3d arrow_pose = convertPose(pose.pose) * Eigen::AngleAxisd(M_PI / 2, Eigen::Vector3d::UnitZ()); geometry_msgs::PoseStamped new_pose = pose; new_pose.pose = convertPose(arrow_pose); return publishArrow(new_pose, color, scale, length); } -bool RvizVisualTools::publishZArrow(const Eigen::Affine3d& pose, colors color, scales scale, double length, +bool RvizVisualTools::publishZArrow(const Eigen::Isometry3d& pose, colors color, scales scale, double length, std::size_t id) { - Eigen::Affine3d arrow_pose = pose * Eigen::AngleAxisd(-M_PI / 2, Eigen::Vector3d::UnitY()); + Eigen::Isometry3d arrow_pose = pose * Eigen::AngleAxisd(-M_PI / 2, Eigen::Vector3d::UnitY()); return publishArrow(convertPose(arrow_pose), color, scale, length, id); } bool RvizVisualTools::publishZArrow(const geometry_msgs::Pose& pose, colors color, scales scale, double length) { - Eigen::Affine3d arrow_pose = convertPose(pose) * Eigen::AngleAxisd(-M_PI / 2, Eigen::Vector3d::UnitY()); + Eigen::Isometry3d arrow_pose = convertPose(pose) * Eigen::AngleAxisd(-M_PI / 2, Eigen::Vector3d::UnitY()); return publishArrow(convertPose(arrow_pose), color, scale, length); } bool RvizVisualTools::publishZArrow(const geometry_msgs::PoseStamped& pose, colors color, scales scale, double length) { - Eigen::Affine3d arrow_pose = convertPose(pose.pose) * Eigen::AngleAxisd(-M_PI / 2, Eigen::Vector3d::UnitY()); + Eigen::Isometry3d arrow_pose = convertPose(pose.pose) * Eigen::AngleAxisd(-M_PI / 2, Eigen::Vector3d::UnitY()); geometry_msgs::PoseStamped new_pose = pose; new_pose.pose = convertPose(arrow_pose); return publishArrow(new_pose, color, scale, length); @@ -1279,13 +1279,13 @@ bool RvizVisualTools::publishZArrow(const geometry_msgs::PoseStamped& pose, colo bool RvizVisualTools::publishZArrow(const geometry_msgs::PoseStamped& pose, colors color, scales scale, double length, std::size_t id) { - Eigen::Affine3d arrow_pose = convertPose(pose.pose) * Eigen::AngleAxisd(-M_PI / 2, Eigen::Vector3d::UnitY()); + Eigen::Isometry3d arrow_pose = convertPose(pose.pose) * Eigen::AngleAxisd(-M_PI / 2, Eigen::Vector3d::UnitY()); geometry_msgs::PoseStamped new_pose = pose; new_pose.pose = convertPose(arrow_pose); return publishArrow(new_pose, color, scale, length, id); } -bool RvizVisualTools::publishArrow(const Eigen::Affine3d& pose, colors color, scales scale, double length, +bool RvizVisualTools::publishArrow(const Eigen::Isometry3d& pose, colors color, scales scale, double length, std::size_t id) { return publishArrow(convertPose(pose), color, scale, length, id); @@ -1394,7 +1394,7 @@ bool RvizVisualTools::publishArrow(const geometry_msgs::Point& start, const geom return publishMarker(arrow_marker_); } -bool RvizVisualTools::publishAxisLabeled(const Eigen::Affine3d& pose, const std::string& label, scales scale, +bool RvizVisualTools::publishAxisLabeled(const Eigen::Isometry3d& pose, const std::string& label, scales scale, colors color) { return publishAxisLabeled(convertPose(pose), label, scale, color); @@ -1420,7 +1420,7 @@ bool RvizVisualTools::publishAxis(const geometry_msgs::Pose& pose, scales scale, return publishAxis(pose, radius * 10.0, radius, ns); } -bool RvizVisualTools::publishAxis(const Eigen::Affine3d& pose, scales scale, const std::string& ns) +bool RvizVisualTools::publishAxis(const Eigen::Isometry3d& pose, scales scale, const std::string& ns) { double radius = getScale(scale).x; return publishAxis(pose, radius * 10.0, radius, ns); @@ -1431,7 +1431,7 @@ bool RvizVisualTools::publishAxis(const geometry_msgs::Pose& pose, double length return publishAxis(convertPose(pose), length, radius, ns); } -bool RvizVisualTools::publishAxis(const Eigen::Affine3d& pose, double length, double radius, const std::string& ns) +bool RvizVisualTools::publishAxis(const Eigen::Isometry3d& pose, double length, double radius, const std::string& ns) { // Use an internal function that will not actually publish anything, so that other makers can combine with an axis // without publishing @@ -1440,30 +1440,30 @@ bool RvizVisualTools::publishAxis(const Eigen::Affine3d& pose, double length, do return true; } -bool RvizVisualTools::publishAxisInternal(const Eigen::Affine3d& pose, double length, double radius, +bool RvizVisualTools::publishAxisInternal(const Eigen::Isometry3d& pose, double length, double radius, const std::string& ns) { // Publish x axis - Eigen::Affine3d x_pose = + Eigen::Isometry3d x_pose = Eigen::Translation3d(length / 2.0, 0, 0) * Eigen::AngleAxisd(M_PI / 2.0, Eigen::Vector3d::UnitY()); x_pose = pose * x_pose; publishCylinder(x_pose, RED, length, radius, ns); // Publish y axis - Eigen::Affine3d y_pose = + Eigen::Isometry3d y_pose = Eigen::Translation3d(0, length / 2.0, 0) * Eigen::AngleAxisd(M_PI / 2.0, Eigen::Vector3d::UnitX()); y_pose = pose * y_pose; publishCylinder(y_pose, GREEN, length, radius, ns); // Publish z axis - Eigen::Affine3d z_pose = Eigen::Translation3d(0, 0, length / 2.0) * Eigen::AngleAxisd(0, Eigen::Vector3d::UnitZ()); + Eigen::Isometry3d z_pose = Eigen::Translation3d(0, 0, length / 2.0) * Eigen::AngleAxisd(0, Eigen::Vector3d::UnitZ()); z_pose = pose * z_pose; publishCylinder(z_pose, BLUE, length, radius, ns); return true; } -bool RvizVisualTools::publishAxisPath(const EigenSTL::vector_Affine3d& path, scales scale, const std::string& ns) +bool RvizVisualTools::publishAxisPath(const EigenSTL::vector_Isometry3d& path, scales scale, const std::string& ns) { // Create the cylinders for (const auto& i : path) @@ -1475,7 +1475,7 @@ bool RvizVisualTools::publishAxisPath(const EigenSTL::vector_Affine3d& path, sca return true; } -bool RvizVisualTools::publishAxisPath(const EigenSTL::vector_Affine3d& path, double length, double radius, +bool RvizVisualTools::publishAxisPath(const EigenSTL::vector_Isometry3d& path, double length, double radius, const std::string& ns) { // Create the cylinders @@ -1510,11 +1510,11 @@ bool RvizVisualTools::publishCylinder(const Eigen::Vector3d& point1, const Eigen Eigen::Vector3d pt_center = getCenterPoint(point1, point2); // Create vector - Eigen::Affine3d pose; + Eigen::Isometry3d pose; pose = getVectorBetweenPoints(pt_center, point2); // Convert pose to be normal to cylindar axis - Eigen::Affine3d rotation; + Eigen::Isometry3d rotation; rotation = Eigen::AngleAxisd(0.5 * M_PI, Eigen::Vector3d::UnitY()); pose = pose * rotation; @@ -1522,7 +1522,7 @@ bool RvizVisualTools::publishCylinder(const Eigen::Vector3d& point1, const Eigen return publishCylinder(convertPose(pose), color, height, radius); } -bool RvizVisualTools::publishCylinder(const Eigen::Affine3d& pose, colors color, double height, double radius, +bool RvizVisualTools::publishCylinder(const Eigen::Isometry3d& pose, colors color, double height, double radius, const std::string& ns) { return publishCylinder(convertPose(pose), color, height, radius, ns); @@ -1557,7 +1557,7 @@ bool RvizVisualTools::publishCylinder(const geometry_msgs::Pose& pose, const std return publishMarker(cylinder_marker_); } -bool RvizVisualTools::publishMesh(const Eigen::Affine3d& pose, const std::string& file_name, colors color, double scale, +bool RvizVisualTools::publishMesh(const Eigen::Isometry3d& pose, const std::string& file_name, colors color, double scale, const std::string& ns, std::size_t id) { return publishMesh(convertPose(pose), file_name, color, scale, ns, id); @@ -1686,7 +1686,7 @@ bool RvizVisualTools::publishCuboid(const geometry_msgs::Point& point1, const ge return publishMarker(cuboid_marker_); } -bool RvizVisualTools::publishCuboid(const Eigen::Affine3d& pose, double depth, double width, double height, +bool RvizVisualTools::publishCuboid(const Eigen::Isometry3d& pose, double depth, double width, double height, colors color) { return publishCuboid(convertPose(pose), depth, width, height, color); @@ -1733,7 +1733,7 @@ bool RvizVisualTools::publishCuboid(const geometry_msgs::Pose& pose, double dept return publishMarker(cuboid_marker_); } -bool RvizVisualTools::publishLine(const Eigen::Affine3d& point1, const Eigen::Affine3d& point2, colors color, +bool RvizVisualTools::publishLine(const Eigen::Isometry3d& point1, const Eigen::Isometry3d& point2, colors color, scales scale) { return publishLine(convertPoseToPoint(point1), convertPoseToPoint(point2), color, scale); @@ -1909,7 +1909,7 @@ bool RvizVisualTools::publishPath(const std::vector& path, return publishPath(path, color, getScale(scale).x, ns); } -bool RvizVisualTools::publishPath(const EigenSTL::vector_Affine3d& path, colors color, scales scale, +bool RvizVisualTools::publishPath(const EigenSTL::vector_Isometry3d& path, colors color, scales scale, const std::string& ns) { return publishPath(path, color, getScale(scale).x, ns); @@ -1957,7 +1957,7 @@ bool RvizVisualTools::publishPath(const EigenSTL::vector_Vector3d& path, colors return true; } -bool RvizVisualTools::publishPath(const EigenSTL::vector_Affine3d& path, colors color, double radius, +bool RvizVisualTools::publishPath(const EigenSTL::vector_Isometry3d& path, colors color, double radius, const std::string& ns) { if (path.size() < 2) @@ -2049,7 +2049,7 @@ bool RvizVisualTools::publishPolygon(const geometry_msgs::Polygon& polygon, colo return publishPath(points, color, scale, ns); } -bool RvizVisualTools::publishWireframeCuboid(const Eigen::Affine3d& pose, double depth, double width, double height, +bool RvizVisualTools::publishWireframeCuboid(const Eigen::Isometry3d& pose, double depth, double width, double height, colors color, const std::string& ns, std::size_t id) { Eigen::Vector3d min_point, max_point; @@ -2058,7 +2058,7 @@ bool RvizVisualTools::publishWireframeCuboid(const Eigen::Affine3d& pose, double return publishWireframeCuboid(pose, min_point, max_point, color, ns, id); } -bool RvizVisualTools::publishWireframeCuboid(const Eigen::Affine3d& pose, const Eigen::Vector3d& min_point, +bool RvizVisualTools::publishWireframeCuboid(const Eigen::Isometry3d& pose, const Eigen::Vector3d& min_point, const Eigen::Vector3d& max_point, colors color, const std::string& ns, std::size_t id) { @@ -2165,7 +2165,7 @@ bool RvizVisualTools::publishWireframeCuboid(const Eigen::Affine3d& pose, const return publishMarker(line_list_marker_); } -bool RvizVisualTools::publishWireframeRectangle(const Eigen::Affine3d& pose, double height, double width, colors color, +bool RvizVisualTools::publishWireframeRectangle(const Eigen::Isometry3d& pose, double height, double width, colors color, scales scale, std::size_t id) { if (id == 0) @@ -2223,7 +2223,7 @@ bool RvizVisualTools::publishWireframeRectangle(const Eigen::Affine3d& pose, dou return publishMarker(line_list_marker_); } -bool RvizVisualTools::publishWireframeRectangle(const Eigen::Affine3d& pose, const Eigen::Vector3d& p1_in, +bool RvizVisualTools::publishWireframeRectangle(const Eigen::Isometry3d& pose, const Eigen::Vector3d& p1_in, const Eigen::Vector3d& p2_in, const Eigen::Vector3d& p3_in, const Eigen::Vector3d& p4_in, colors color, scales scale) { @@ -2381,13 +2381,13 @@ bool RvizVisualTools::publishSpheres(const std::vector& po return publishMarker(spheres_marker_); } -bool RvizVisualTools::publishText(const Eigen::Affine3d& pose, const std::string& text, colors color, scales scale, +bool RvizVisualTools::publishText(const Eigen::Isometry3d& pose, const std::string& text, colors color, scales scale, bool static_id) { return publishText(convertPose(pose), text, color, getScale(scale), static_id); } -bool RvizVisualTools::publishText(const Eigen::Affine3d& pose, const std::string& text, colors color, +bool RvizVisualTools::publishText(const Eigen::Isometry3d& pose, const std::string& text, colors color, const geometry_msgs::Vector3 scale, bool static_id) { return publishText(convertPose(pose), text, color, scale, static_id); @@ -2432,34 +2432,34 @@ bool RvizVisualTools::publishText(const geometry_msgs::Pose& pose, const std::st return true; } -geometry_msgs::Pose RvizVisualTools::convertPose(const Eigen::Affine3d& pose) +geometry_msgs::Pose RvizVisualTools::convertPose(const Eigen::Isometry3d& pose) { geometry_msgs::Pose pose_msg; tf::poseEigenToMsg(pose, pose_msg); return pose_msg; } -void RvizVisualTools::convertPoseSafe(const Eigen::Affine3d& pose, geometry_msgs::Pose& pose_msg) +void RvizVisualTools::convertPoseSafe(const Eigen::Isometry3d& pose, geometry_msgs::Pose& pose_msg) { tf::poseEigenToMsg(pose, pose_msg); } -Eigen::Affine3d RvizVisualTools::convertPose(const geometry_msgs::Pose& pose) +Eigen::Isometry3d RvizVisualTools::convertPose(const geometry_msgs::Pose& pose) { - Eigen::Affine3d shared_pose_eigen_; + Eigen::Isometry3d shared_pose_eigen_; tf::poseMsgToEigen(pose, shared_pose_eigen_); return shared_pose_eigen_; } -void RvizVisualTools::convertPoseSafe(const geometry_msgs::Pose& pose_msg, Eigen::Affine3d& pose) +void RvizVisualTools::convertPoseSafe(const geometry_msgs::Pose& pose_msg, Eigen::Isometry3d& pose) { tf::poseMsgToEigen(pose_msg, pose); } -Eigen::Affine3d RvizVisualTools::convertPoint32ToPose(const geometry_msgs::Point32& point) +Eigen::Isometry3d RvizVisualTools::convertPoint32ToPose(const geometry_msgs::Point32& point) { - Eigen::Affine3d shared_pose_eigen_; - shared_pose_eigen_ = Eigen::Affine3d::Identity(); + Eigen::Isometry3d shared_pose_eigen_; + shared_pose_eigen_ = Eigen::Isometry3d::Identity(); shared_pose_eigen_.translation().x() = point.x; shared_pose_eigen_.translation().y() = point.y; shared_pose_eigen_.translation().z() = point.z; @@ -2477,15 +2477,15 @@ geometry_msgs::Pose RvizVisualTools::convertPointToPose(const geometry_msgs::Poi return pose_msg; } -Eigen::Affine3d RvizVisualTools::convertPointToPose(const Eigen::Vector3d& point) +Eigen::Isometry3d RvizVisualTools::convertPointToPose(const Eigen::Vector3d& point) { - Eigen::Affine3d shared_pose_eigen_; - shared_pose_eigen_ = Eigen::Affine3d::Identity(); + Eigen::Isometry3d shared_pose_eigen_; + shared_pose_eigen_ = Eigen::Isometry3d::Identity(); shared_pose_eigen_.translation() = point; return shared_pose_eigen_; } -geometry_msgs::Point RvizVisualTools::convertPoseToPoint(const Eigen::Affine3d& pose) +geometry_msgs::Point RvizVisualTools::convertPoseToPoint(const Eigen::Isometry3d& pose) { geometry_msgs::Pose pose_msg; tf::poseEigenToMsg(pose, pose_msg); @@ -2537,10 +2537,10 @@ geometry_msgs::Point RvizVisualTools::convertPoint(const Eigen::Vector3d& point) return point_msg; } -Eigen::Affine3d RvizVisualTools::convertFromXYZRPY(double tx, double ty, double tz, double rx, double ry, double rz, +Eigen::Isometry3d RvizVisualTools::convertFromXYZRPY(double tx, double ty, double tz, double rx, double ry, double rz, EulerConvention convention) { - Eigen::Affine3d result; + Eigen::Isometry3d result; switch (convention) { @@ -2567,7 +2567,7 @@ Eigen::Affine3d RvizVisualTools::convertFromXYZRPY(double tx, double ty, double return result; } -Eigen::Affine3d RvizVisualTools::convertFromXYZRPY(const std::vector& transform6, EulerConvention convention) +Eigen::Isometry3d RvizVisualTools::convertFromXYZRPY(const std::vector& transform6, EulerConvention convention) { if (transform6.size() != 6) { @@ -2579,13 +2579,13 @@ Eigen::Affine3d RvizVisualTools::convertFromXYZRPY(const std::vector& tr convention); } -void RvizVisualTools::convertToXYZRPY(const Eigen::Affine3d& pose, std::vector& xyzrpy) +void RvizVisualTools::convertToXYZRPY(const Eigen::Isometry3d& pose, std::vector& xyzrpy) { xyzrpy.resize(6); convertToXYZRPY(pose, xyzrpy[0], xyzrpy[1], xyzrpy[2], xyzrpy[3], xyzrpy[4], xyzrpy[5]); } -void RvizVisualTools::convertToXYZRPY(const Eigen::Affine3d& pose, double& x, double& y, double& z, double& roll, +void RvizVisualTools::convertToXYZRPY(const Eigen::Isometry3d& pose, double& x, double& y, double& z, double& roll, double& pitch, double& yaw) { x = pose(0, 3); @@ -2601,7 +2601,7 @@ void RvizVisualTools::convertToXYZRPY(const Eigen::Affine3d& pose, double& x, do void RvizVisualTools::generateRandomPose(geometry_msgs::Pose& pose, RandomPoseBounds pose_bounds) { - Eigen::Affine3d pose_eigen; + Eigen::Isometry3d pose_eigen; generateRandomPose(pose_eigen, pose_bounds); pose = convertPose(pose_eigen); } @@ -2619,7 +2619,7 @@ void RvizVisualTools::generateRandomCuboid(geometry_msgs::Pose& cuboid_pose, dou generateRandomPose(cuboid_pose, pose_bounds); } -void RvizVisualTools::generateRandomPose(Eigen::Affine3d& pose, RandomPoseBounds pose_bounds) +void RvizVisualTools::generateRandomPose(Eigen::Isometry3d& pose, RandomPoseBounds pose_bounds) { // Error check elevation & azimuth angles // 0 <= elevation <= pi @@ -2681,7 +2681,7 @@ void RvizVisualTools::generateEmptyPose(geometry_msgs::Pose& pose) pose.orientation.w = 1; } -bool RvizVisualTools::posesEqual(const Eigen::Affine3d& pose1, const Eigen::Affine3d& pose2, double threshold) +bool RvizVisualTools::posesEqual(const Eigen::Isometry3d& pose1, const Eigen::Isometry3d& pose2, double threshold) { static const std::size_t NUM_VARS = 16; // size of eigen matrix @@ -2725,7 +2725,7 @@ void RvizVisualTools::printTranslation(const Eigen::Vector3d& translation) std::cout << "T.xyz = [" << translation.x() << ", " << translation.y() << ", " << translation.z() << "]" << std::endl; } -void RvizVisualTools::printTransform(const Eigen::Affine3d& transform) +void RvizVisualTools::printTransform(const Eigen::Isometry3d& transform) { Eigen::Quaterniond q(transform.rotation()); std::cout << "T.xyz = [" << transform.translation().x() << ", " << transform.translation().y() << ", " @@ -2733,7 +2733,7 @@ void RvizVisualTools::printTransform(const Eigen::Affine3d& transform) << q.w() << "]" << std::endl; } -void RvizVisualTools::printTransformRPY(const Eigen::Affine3d& transform) +void RvizVisualTools::printTransformRPY(const Eigen::Isometry3d& transform) { // R-P-Y / X-Y-Z / 0-1-2 Euler Angle Standard Eigen::Vector3d vec = transform.rotation().eulerAngles(0, 1, 2); @@ -2741,7 +2741,7 @@ void RvizVisualTools::printTransformRPY(const Eigen::Affine3d& transform) << transform.translation().z() << ", " << vec[0] << ", " << vec[1] << ", " << vec[2] << "]\n"; } -void RvizVisualTools::printTransformFull(const Eigen::Affine3d& transform) +void RvizVisualTools::printTransformFull(const Eigen::Isometry3d& transform) { std::cout << "T.xyz = [" << transform.translation().x() << ", " << transform.translation().y() << ", " << transform.translation().z() << "], R = \n" diff --git a/src/rviz_visual_tools_demo.cpp b/src/rviz_visual_tools_demo.cpp index 480dd25..abd4bac 100644 --- a/src/rviz_visual_tools_demo.cpp +++ b/src/rviz_visual_tools_demo.cpp @@ -79,9 +79,9 @@ class RvizVisualToolsDemo visual_tools_->enableBatchPublishing(); } - void publishLabelHelper(const Eigen::Affine3d& pose, const std::string& label) + void publishLabelHelper(const Eigen::Isometry3d& pose, const std::string& label) { - Eigen::Affine3d pose_copy = pose; + Eigen::Isometry3d pose_copy = pose; pose_copy.translation().x() -= 0.2; visual_tools_->publishText(pose_copy, label, rvt::WHITE, rvt::XXLARGE, false); } @@ -89,8 +89,8 @@ class RvizVisualToolsDemo void testRows(double& x_location) { // Create pose - Eigen::Affine3d pose1 = Eigen::Affine3d::Identity(); - Eigen::Affine3d pose2 = Eigen::Affine3d::Identity(); + Eigen::Isometry3d pose1 = Eigen::Isometry3d::Identity(); + Eigen::Isometry3d pose2 = Eigen::Isometry3d::Identity(); pose1.translation().x() = x_location; @@ -137,7 +137,7 @@ class RvizVisualToolsDemo // -------------------------------------------------------------------- ROS_INFO_STREAM_NAMED(name_, "Displaying Arrows"); - pose1 = Eigen::Affine3d::Identity(); + pose1 = Eigen::Isometry3d::Identity(); y += space_between_rows; pose1.translation().y() = y; step = 0.025; @@ -158,8 +158,8 @@ class RvizVisualToolsDemo ROS_INFO_STREAM_NAMED(name_, "Displaying Rectangular Cuboid"); double cuboid_max_size = 0.075; double cuboid_min_size = 0.01; - pose1 = Eigen::Affine3d::Identity(); - pose2 = Eigen::Affine3d::Identity(); + pose1 = Eigen::Isometry3d::Identity(); + pose2 = Eigen::Isometry3d::Identity(); y += space_between_rows; pose1.translation().y() = y; pose2.translation().y() = y; @@ -185,8 +185,8 @@ class RvizVisualToolsDemo ROS_INFO_STREAM_NAMED(name_, "Displaying Lines"); double line_max_size = 0.075; double line_min_size = 0.01; - pose1 = Eigen::Affine3d::Identity(); - pose2 = Eigen::Affine3d::Identity(); + pose1 = Eigen::Isometry3d::Identity(); + pose2 = Eigen::Isometry3d::Identity(); y += space_between_rows; pose1.translation().y() = y; pose2.translation().y() = y; @@ -210,7 +210,7 @@ class RvizVisualToolsDemo // -------------------------------------------------------------------- ROS_INFO_STREAM_NAMED(name_, "Displaying Cylinder"); - pose1 = Eigen::Affine3d::Identity(); + pose1 = Eigen::Isometry3d::Identity(); y += space_between_rows; pose1.translation().y() = y; step = 0.025; @@ -229,7 +229,7 @@ class RvizVisualToolsDemo // -------------------------------------------------------------------- ROS_INFO_STREAM_NAMED(name_, "Displaying Axis Cone"); - pose1 = Eigen::Affine3d::Identity(); + pose1 = Eigen::Isometry3d::Identity(); y += space_between_rows; pose1.translation().y() = y; step = 0.025; @@ -252,7 +252,7 @@ class RvizVisualToolsDemo // -------------------------------------------------------------------- ROS_INFO_STREAM_NAMED(name_, "Displaying Wireframe Cuboid"); - pose1 = Eigen::Affine3d::Identity(); + pose1 = Eigen::Isometry3d::Identity(); y += space_between_rows; pose1.translation().y() = y; step = 0.1; @@ -275,7 +275,7 @@ class RvizVisualToolsDemo // -------------------------------------------------------------------- ROS_INFO_STREAM_NAMED(name_, "Displaying Sized Wireframe Cuboid"); - pose1 = Eigen::Affine3d::Identity(); + pose1 = Eigen::Isometry3d::Identity(); y += space_between_rows; pose1.translation().y() = y; step = 0.1; @@ -295,7 +295,7 @@ class RvizVisualToolsDemo // -------------------------------------------------------------------- ROS_INFO_STREAM_NAMED(name_, "Displaying Planes"); - pose1 = Eigen::Affine3d::Identity(); + pose1 = Eigen::Isometry3d::Identity(); y += space_between_rows; pose1.translation().y() = y; step = 0.2; @@ -317,7 +317,7 @@ class RvizVisualToolsDemo // -------------------------------------------------------------------- ROS_INFO_STREAM_NAMED(name_, "Displaying Graph"); - pose1 = Eigen::Affine3d::Identity(); + pose1 = Eigen::Isometry3d::Identity(); y += space_between_rows; pose1.translation().y() = y; step = 0.1; @@ -373,8 +373,8 @@ class RvizVisualToolsDemo // -------------------------------------------------------------------- ROS_INFO_STREAM_NAMED(name_, "Displaying Multi-Color Path"); - pose1 = Eigen::Affine3d::Identity(); - pose2 = Eigen::Affine3d::Identity(); + pose1 = Eigen::Isometry3d::Identity(); + pose2 = Eigen::Isometry3d::Identity(); y += space_between_rows; pose1.translation().y() = y; step = 0.1; @@ -414,8 +414,8 @@ class RvizVisualToolsDemo void testSize(double& x_location, scales scale) { // Create pose - Eigen::Affine3d pose1 = Eigen::Affine3d::Identity(); - Eigen::Affine3d pose2 = Eigen::Affine3d::Identity(); + Eigen::Isometry3d pose1 = Eigen::Isometry3d::Identity(); + Eigen::Isometry3d pose2 = Eigen::Isometry3d::Identity(); // Reusable vector of 2 colors std::vector colors; @@ -545,8 +545,8 @@ class RvizVisualToolsDemo ROS_INFO_STREAM_NAMED(name_, "Testing sizes of marker scale"); // Create pose - Eigen::Affine3d pose1 = Eigen::Affine3d::Identity(); - Eigen::Affine3d pose2; + Eigen::Isometry3d pose1 = Eigen::Isometry3d::Identity(); + Eigen::Isometry3d pose2; // Show test label pose1.translation().x() = x_location - 0.1; diff --git a/src/tf_visual_tools.cpp b/src/tf_visual_tools.cpp index c148a63..69a8d38 100644 --- a/src/tf_visual_tools.cpp +++ b/src/tf_visual_tools.cpp @@ -54,7 +54,7 @@ TFVisualTools::TFVisualTools(double loop_hz) ROS_INFO_STREAM_NAMED("tf_visual_tools", "TFVisualTools Ready."); } -bool TFVisualTools::publishTransform(const Eigen::Affine3d& transform, const std::string& from_frame, +bool TFVisualTools::publishTransform(const Eigen::Isometry3d& transform, const std::string& from_frame, const std::string& to_frame) { ROS_DEBUG_STREAM_NAMED("tf_visual_tools", "Publishing transform from " << from_frame << " to " << to_frame); diff --git a/tests/rvt_test.cpp b/tests/rvt_test.cpp index 0bc75b9..bd6db65 100644 --- a/tests/rvt_test.cpp +++ b/tests/rvt_test.cpp @@ -64,7 +64,7 @@ class RVTTest return true; } - bool testAffine3d(const std::string& id, const Eigen::Affine3d& expect, const Eigen::Affine3d& actual) + bool testIsometry3d(const std::string& id, const Eigen::Isometry3d& expect, const Eigen::Isometry3d& actual) { static const double EPSILON = 0.000001; EXPECT_GT(EPSILON, fabs(expect.translation().x() - actual.translation().x())) @@ -112,7 +112,7 @@ TEST(RVTTest, initialize) TEST(RVTTest, test_rpy_conversions) { // Identity conversions with RPY - Eigen::Affine3d expected_affine = Eigen::Affine3d::Identity(); + Eigen::Isometry3d expected_affine = Eigen::Isometry3d::Identity(); std::vector xyzrpy; base.visual_tools_->convertToXYZRPY(expected_affine, xyzrpy); std::vector expected_vector; @@ -125,8 +125,8 @@ TEST(RVTTest, test_rpy_conversions) EXPECT_TRUE(base.testVector("Identity: ", expected_vector, xyzrpy)); // Identity conversion back to Eigen - Eigen::Affine3d expected_affine2 = base.visual_tools_->convertFromXYZRPY(xyzrpy, rviz_visual_tools::XYZ); - EXPECT_TRUE(base.testAffine3d("Identity convert back", expected_affine, expected_affine2)); + Eigen::Isometry3d expected_affine2 = base.visual_tools_->convertFromXYZRPY(xyzrpy, rviz_visual_tools::XYZ); + EXPECT_TRUE(base.testIsometry3d("Identity convert back", expected_affine, expected_affine2)); // ------------------------------------------------------------------- // Translation conversions to RPY @@ -141,17 +141,17 @@ TEST(RVTTest, test_rpy_conversions) // Translation convertion back to Eigen expected_affine2 = base.visual_tools_->convertFromXYZRPY(xyzrpy, rviz_visual_tools::XYZ); - EXPECT_TRUE(base.testAffine3d("123 convert back", expected_affine, expected_affine2)); + EXPECT_TRUE(base.testIsometry3d("123 convert back", expected_affine, expected_affine2)); // Translation convertion back to Eigen via long function expected_affine2 = base.visual_tools_->convertFromXYZRPY(xyzrpy[0], xyzrpy[1], xyzrpy[2], xyzrpy[3], xyzrpy[4], xyzrpy[5], rviz_visual_tools::XYZ); - EXPECT_TRUE(base.testAffine3d("123 convert back long", expected_affine, expected_affine2)); + EXPECT_TRUE(base.testIsometry3d("123 convert back long", expected_affine, expected_affine2)); // Translation convertion back to Eigen via NEW long function expected_affine2 = base.visual_tools_->convertFromXYZRPY(xyzrpy[0], xyzrpy[1], xyzrpy[2], xyzrpy[3], xyzrpy[4], xyzrpy[5], rviz_visual_tools::XYZ); - EXPECT_TRUE(base.testAffine3d("123 convert back new long", expected_affine, expected_affine2)); + EXPECT_TRUE(base.testIsometry3d("123 convert back new long", expected_affine, expected_affine2)); // ------------------------------------------------------------------- // Rotation conversions to RPY @@ -162,17 +162,17 @@ TEST(RVTTest, test_rpy_conversions) // Rotation convertion back to Eigen expected_affine2 = base.visual_tools_->convertFromXYZRPY(xyzrpy, rviz_visual_tools::XYZ); - EXPECT_TRUE(base.testAffine3d("123 convert back", expected_affine, expected_affine2)); + EXPECT_TRUE(base.testIsometry3d("123 convert back", expected_affine, expected_affine2)); // Rotation convertion back to Eigen via long function expected_affine2 = base.visual_tools_->convertFromXYZRPY(xyzrpy[0], xyzrpy[1], xyzrpy[2], xyzrpy[3], xyzrpy[4], xyzrpy[5], rviz_visual_tools::XYZ); - EXPECT_TRUE(base.testAffine3d("123 convert back long", expected_affine, expected_affine2)); + EXPECT_TRUE(base.testIsometry3d("123 convert back long", expected_affine, expected_affine2)); // Rotation convertion back to Eigen via NEW long function expected_affine2 = base.visual_tools_->convertFromXYZRPY(xyzrpy[0], xyzrpy[1], xyzrpy[2], xyzrpy[3], xyzrpy[4], xyzrpy[5], rviz_visual_tools::XYZ); - EXPECT_TRUE(base.testAffine3d("123 convert back new long", expected_affine, expected_affine2)); + EXPECT_TRUE(base.testIsometry3d("123 convert back new long", expected_affine, expected_affine2)); } /* Main ------------------------------------------------------------------------------------- */