7171
7272// Import/export for windows dll's and visibility for gcc shared libraries.
7373
74- #ifdef ROS_BUILD_SHARED_LIBS // ros is being built around shared libraries
75- #ifdef rviz_visual_tools_EXPORTS // we are building a shared lib/dll
76- #define RVIZ_VISUAL_TOOLS_DECL ROS_HELPER_EXPORT
77- #else // we are using shared lib/dll
78- #define RVIZ_VISUAL_TOOLS_DECL ROS_HELPER_IMPORT
79- #endif
80- #else // ros is being built around static libraries
81- #define RVIZ_VISUAL_TOOLS_DECL
74+ #ifdef ROS_BUILD_SHARED_LIBS // ros is being built around shared libraries
75+ #ifdef rviz_visual_tools_EXPORTS // we are building a shared lib/dll
76+ #define RVIZ_VISUAL_TOOLS_DECL ROS_HELPER_EXPORT
77+ #else // we are using shared lib/dll
78+ #define RVIZ_VISUAL_TOOLS_DECL ROS_HELPER_IMPORT
79+ #endif
80+ #else // ros is being built around static libraries
81+ #define RVIZ_VISUAL_TOOLS_DECL
8282#endif
8383
8484namespace rviz_visual_tools
@@ -197,7 +197,8 @@ class RvizVisualTools
197197 * \param marker_topic - rostopic to publish markers to - your Rviz display should match
198198 * \param nh - optional ros node handle - defaults to "~"
199199 */
200- explicit RvizVisualTools (std::string base_frame, std::string marker_topic = RVIZ_MARKER_TOPIC, ros::NodeHandle nh = ros::NodeHandle(" ~" ));
200+ explicit RvizVisualTools (std::string base_frame, std::string marker_topic = RVIZ_MARKER_TOPIC,
201+ ros::NodeHandle nh = ros::NodeHandle(" ~" ));
201202 /* *
202203 * \brief Deconstructor
203204 */
@@ -426,8 +427,8 @@ class RvizVisualTools
426427 * \param y_width - Y-size of the visualized plane [meters]
427428 * \return true on success
428429 */
429- bool publishABCDPlane (const double A, const double B, const double C, const double D,
430- colors color=TRANSLUCENT, double x_width = 1.0 , double y_width = 1.0 );
430+ bool publishABCDPlane (const double A, const double B, const double C, const double D, colors color = TRANSLUCENT,
431+ double x_width = 1.0 , double y_width = 1.0 );
431432
432433 /* *
433434 * \brief Display the XY plane of a given pose
@@ -485,8 +486,8 @@ class RvizVisualTools
485486 const std::string& ns = " Sphere" , std::size_t id = 0 );
486487 bool publishSphere (const geometry_msgs::Pose& pose, const std_msgs::ColorRGBA& color,
487488 const geometry_msgs::Vector3 scale, const std::string& ns = " Sphere" , std::size_t id = 0 );
488- bool publishSphere (const Eigen::Isometry3d& pose, const std_msgs::ColorRGBA& color, const geometry_msgs::Vector3 scale,
489- const std::string& ns = " Sphere" , std::size_t id = 0 );
489+ bool publishSphere (const Eigen::Isometry3d& pose, const std_msgs::ColorRGBA& color,
490+ const geometry_msgs::Vector3 scale, const std::string& ns = " Sphere" , std::size_t id = 0 );
490491 bool publishSphere (const Eigen::Vector3d& point, const std_msgs::ColorRGBA& color, const geometry_msgs::Vector3 scale,
491492 const std::string& ns = " Sphere" , std::size_t id = 0 );
492493 bool publishSphere (const geometry_msgs::PoseStamped& pose, colors color, const geometry_msgs::Vector3 scale,
@@ -668,10 +669,8 @@ class RvizVisualTools
668669 const std::string& ns = " Path" );
669670 bool publishPath (const std::vector<geometry_msgs::Point>& path, colors color, scales scale,
670671 const std::string& ns = " Path" );
671- bool publishPath (const EigenSTL::vector_Isometry3d& path, colors color, scales scale,
672- const std::string& ns = " Path" );
673- bool publishPath (const EigenSTL::vector_Vector3d& path, colors color, scales scale,
674- const std::string& ns = " Path" );
672+ bool publishPath (const EigenSTL::vector_Isometry3d& path, colors color, scales scale, const std::string& ns = " Path" );
673+ bool publishPath (const EigenSTL::vector_Vector3d& path, colors color, scales scale, const std::string& ns = " Path" );
675674 bool publishPath (const std::vector<geometry_msgs::Point>& path, colors color = RED, double radius = 0.01 ,
676675 const std::string& ns = " Path" );
677676 bool publishPath (const EigenSTL::vector_Vector3d& path, colors color = RED, double radius = 0.01 ,
@@ -861,8 +860,8 @@ class RvizVisualTools
861860 */
862861 bool publishMesh (const Eigen::Isometry3d& pose, const shape_msgs::Mesh& mesh, colors color = CLEAR, double scale = 1 ,
863862 const std::string& ns = " mesh" , std::size_t id = 0 );
864- bool publishMesh (const geometry_msgs::Pose& pose, const shape_msgs::Mesh& mesh, colors color = CLEAR, double scale = 1 ,
865- const std::string& ns = " mesh" , std::size_t id = 0 );
863+ bool publishMesh (const geometry_msgs::Pose& pose, const shape_msgs::Mesh& mesh, colors color = CLEAR,
864+ double scale = 1 , const std::string& ns = " mesh" , std::size_t id = 0 );
866865
867866 /* *
868867 * \brief Display a graph
@@ -993,9 +992,9 @@ class RvizVisualTools
993992 @param convention - default is rviz_visual_tools::XYZ
994993 */
995994 static Eigen::Isometry3d convertFromXYZRPY (double tx, double ty, double tz, double rx, double ry, double rz,
996- EulerConvention convention); // ZYX is ROS standard
995+ EulerConvention convention); // ZYX is ROS standard
997996 static Eigen::Isometry3d convertFromXYZRPY (const std::vector<double >& transform6,
998- EulerConvention convention); // ZYX is ROS standard
997+ EulerConvention convention); // ZYX is ROS standard
999998
1000999 // TODO(davetcoleman): add opposite conversion that uses Eigen::Vector3d rpy = pose.rotation().eulerAngles(0, 1, 2);
10011000
@@ -1006,8 +1005,8 @@ class RvizVisualTools
10061005 * \param output vector of size 6 in order xyz rpy
10071006 */
10081007 static void convertToXYZRPY (const Eigen::Isometry3d& pose, std::vector<double >& xyzrpy);
1009- static void convertToXYZRPY (const Eigen::Isometry3d& pose, double & x, double & y, double & z, double & roll, double & pitch,
1010- double & yaw);
1008+ static void convertToXYZRPY (const Eigen::Isometry3d& pose, double & x, double & y, double & z, double & roll,
1009+ double & pitch, double & yaw);
10111010 /* *
10121011 * \brief Create a random pose within bounds of random_pose_bounds_
10131012 * \param Pose to fill in
0 commit comments