File tree Expand file tree Collapse file tree 1 file changed +14
-2
lines changed Expand file tree Collapse file tree 1 file changed +14
-2
lines changed Original file line number Diff line number Diff line change @@ -1383,8 +1383,14 @@ bool MoveItVisualTools::publishTrajectoryLine(const moveit_msgs::msg::RobotTraje
1383
1383
const moveit::core::JointModelGroup* arm_jmg,
1384
1384
const rviz_visual_tools::Colors& color)
1385
1385
{
1386
+ if (!arm_jmg)
1387
+ {
1388
+ RCLCPP_FATAL_STREAM (LOGGER, " arm_jmg is NULL" );
1389
+ return false ;
1390
+ }
1391
+
1386
1392
std::vector<const moveit::core::LinkModel*> tips;
1387
- if (!arm_jmg->getEndEffectorTips (tips))
1393
+ if (!arm_jmg->getEndEffectorTips (tips) || tips. empty () )
1388
1394
{
1389
1395
RCLCPP_ERROR_STREAM (LOGGER, " Unable to get end effector tips from jmg" );
1390
1396
return false ;
@@ -1411,8 +1417,14 @@ bool MoveItVisualTools::publishTrajectoryLine(const robot_trajectory::RobotTraje
1411
1417
const moveit::core::JointModelGroup* arm_jmg,
1412
1418
const rviz_visual_tools::Colors& color)
1413
1419
{
1420
+ if (!arm_jmg)
1421
+ {
1422
+ RCLCPP_FATAL_STREAM (LOGGER, " arm_jmg is NULL" );
1423
+ return false ;
1424
+ }
1425
+
1414
1426
std::vector<const moveit::core::LinkModel*> tips;
1415
- if (!arm_jmg->getEndEffectorTips (tips))
1427
+ if (!arm_jmg->getEndEffectorTips (tips) || tips. empty () )
1416
1428
{
1417
1429
RCLCPP_ERROR_STREAM (LOGGER, " Unable to get end effector tips from jmg" );
1418
1430
return false ;
You can’t perform that action at this time.
0 commit comments