Skip to content

Commit 5168a83

Browse files
authored
publishTrajectoryLine(): issue error when no end-effector tips are found (#127)
1 parent 40dd5b4 commit 5168a83

File tree

1 file changed

+14
-2
lines changed

1 file changed

+14
-2
lines changed

src/moveit_visual_tools.cpp

Lines changed: 14 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1383,8 +1383,14 @@ bool MoveItVisualTools::publishTrajectoryLine(const moveit_msgs::msg::RobotTraje
13831383
const moveit::core::JointModelGroup* arm_jmg,
13841384
const rviz_visual_tools::Colors& color)
13851385
{
1386+
if (!arm_jmg)
1387+
{
1388+
RCLCPP_FATAL_STREAM(LOGGER, "arm_jmg is NULL");
1389+
return false;
1390+
}
1391+
13861392
std::vector<const moveit::core::LinkModel*> tips;
1387-
if (!arm_jmg->getEndEffectorTips(tips))
1393+
if (!arm_jmg->getEndEffectorTips(tips) || tips.empty())
13881394
{
13891395
RCLCPP_ERROR_STREAM(LOGGER, "Unable to get end effector tips from jmg");
13901396
return false;
@@ -1411,8 +1417,14 @@ bool MoveItVisualTools::publishTrajectoryLine(const robot_trajectory::RobotTraje
14111417
const moveit::core::JointModelGroup* arm_jmg,
14121418
const rviz_visual_tools::Colors& color)
14131419
{
1420+
if (!arm_jmg)
1421+
{
1422+
RCLCPP_FATAL_STREAM(LOGGER, "arm_jmg is NULL");
1423+
return false;
1424+
}
1425+
14141426
std::vector<const moveit::core::LinkModel*> tips;
1415-
if (!arm_jmg->getEndEffectorTips(tips))
1427+
if (!arm_jmg->getEndEffectorTips(tips) || tips.empty())
14161428
{
14171429
RCLCPP_ERROR_STREAM(LOGGER, "Unable to get end effector tips from jmg");
14181430
return false;

0 commit comments

Comments
 (0)