@@ -222,26 +222,26 @@ class MoveItVisualTools : public rviz_visual_tools::RvizVisualTools
222222 */
223223 bool publishEEMarkers (const Eigen::Isometry3d& pose, const robot_model::JointModelGroup* ee_jmg,
224224 const std::vector<double >& ee_joint_pos,
225- const rviz_visual_tools::colors& color = rviz_visual_tools::CLEAR ,
225+ const rviz_visual_tools::colors& color = rviz_visual_tools::DEFAULT ,
226226 const std::string& ns = " end_effector" )
227227 {
228228 return publishEEMarkers (convertPose (pose), ee_jmg, ee_joint_pos, color, ns);
229229 }
230230 bool publishEEMarkers (const Eigen::Isometry3d& pose, const robot_model::JointModelGroup* ee_jmg,
231- const rviz_visual_tools::colors& color = rviz_visual_tools::CLEAR ,
231+ const rviz_visual_tools::colors& color = rviz_visual_tools::DEFAULT ,
232232 const std::string& ns = " end_effector" )
233233 {
234234 return publishEEMarkers (convertPose (pose), ee_jmg, {}, color, ns);
235235 }
236236 bool publishEEMarkers (const geometry_msgs::Pose& pose, const robot_model::JointModelGroup* ee_jmg,
237- const rviz_visual_tools::colors& color = rviz_visual_tools::CLEAR ,
237+ const rviz_visual_tools::colors& color = rviz_visual_tools::DEFAULT ,
238238 const std::string& ns = " end_effector" )
239239 {
240240 return publishEEMarkers (pose, ee_jmg, {}, color, ns);
241241 }
242242 bool publishEEMarkers (const geometry_msgs::Pose& pose, const robot_model::JointModelGroup* ee_jmg,
243243 const std::vector<double >& ee_joint_pos,
244- const rviz_visual_tools::colors& color = rviz_visual_tools::CLEAR ,
244+ const rviz_visual_tools::colors& color = rviz_visual_tools::DEFAULT ,
245245 const std::string& ns = " end_effector" );
246246
247247 /* *
@@ -255,6 +255,7 @@ class MoveItVisualTools : public rviz_visual_tools::RvizVisualTools
255255
256256 /* *
257257 * \brief Display an animated vector of grasps including its approach movement in Rviz
258+ * Note this function calls trigger() automatically in order to achieve animations
258259 * \param possible_grasps - a set of grasp positions to visualize
259260 * \param ee_jmg - the set of joints to use, e.g. the MoveIt planning group, e.g. "left_arm"
260261 * \param animate_speed - how fast the gripper approach is animated, optional
@@ -264,6 +265,7 @@ class MoveItVisualTools : public rviz_visual_tools::RvizVisualTools
264265
265266 /* *
266267 * \brief Animate a single grasp in its movement direction
268+ * Note this function calls trigger() automatically in order to achieve animations
267269 * \param grasp
268270 * \param ee_jmg - the set of joints to use, e.g. the MoveIt planning group, e.g. "left_arm"
269271 * \param animate_speed - how fast the gripper approach is animated
0 commit comments