Skip to content

Commit 737a15f

Browse files
committed
Fix for missing end effector markers because clear
- Do not change the default color to clear - Addresses issues in moveit_grasps - Minor cleanup of EE functions
1 parent 883beb7 commit 737a15f

File tree

2 files changed

+17
-12
lines changed

2 files changed

+17
-12
lines changed

include/moveit_visual_tools/moveit_visual_tools.h

Lines changed: 6 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -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

src/moveit_visual_tools.cpp

Lines changed: 11 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -373,9 +373,6 @@ bool MoveItVisualTools::publishEEMarkers(const geometry_msgs::Pose& pose, const
373373
Eigen::Isometry3d eigen_goal_ee_pose = convertPose(pose);
374374
Eigen::Isometry3d eigen_this_marker;
375375

376-
// publishArrow( pose, rviz_visual_tools::RED, rviz_visual_tools::LARGE );
377-
378-
// -----------------------------------------------------------------------------------------------
379376
// Process each link of the end effector
380377
for (std::size_t i = 0; i < ee_markers_map_[ee_jmg].markers.size(); ++i)
381378
{
@@ -393,15 +390,23 @@ bool MoveItVisualTools::publishEEMarkers(const geometry_msgs::Pose& pose, const
393390
ee_markers_map_[ee_jmg].markers[i].lifetime = marker_lifetime_;
394391

395392
// Color
396-
ee_markers_map_[ee_jmg].markers[i].color = getColor(color);
393+
if (color != rviz_visual_tools::DEFAULT)
394+
ee_markers_map_[ee_jmg].markers[i].color = getColor(color);
397395

398396
// Convert pose
399397
eigen_this_marker = eigen_goal_ee_pose * ee_poses_map_[ee_jmg][i];
400398
ee_markers_map_[ee_jmg].markers[i].pose = convertPose(eigen_this_marker);
401399
}
402400

403401
// Helper for publishing rviz markers
404-
return publishMarkers(ee_markers_map_[ee_jmg]);
402+
// Does not require trigger() because publishing array auto-triggers
403+
if (!publishMarkers(ee_markers_map_[ee_jmg]))
404+
{
405+
ROS_WARN_STREAM_NAMED(LOGNAME, "Unable to publish EE markers");
406+
return false;
407+
}
408+
409+
return true;
405410
}
406411

407412
bool MoveItVisualTools::publishGrasps(const std::vector<moveit_msgs::Grasp>& possible_grasps,
@@ -511,10 +516,8 @@ bool MoveItVisualTools::publishAnimatedGrasp(const moveit_msgs::Grasp& grasp,
511516
// Convert eigen pre-grasp position back to regular message
512517
pre_grasp_pose = tf2::toMsg(pre_grasp_pose_eigen);
513518

514-
// publishArrow(pre_grasp_pose, moveit_visual_tools::BLUE);
515519
publishEEMarkers(pre_grasp_pose, ee_jmg);
516-
if (batch_publishing_enabled_)
517-
trigger();
520+
518521
ros::Duration(animate_speed).sleep();
519522

520523
// Pause more at initial pose for debugging purposes

0 commit comments

Comments
 (0)