Skip to content

Commit

Permalink
MoveRelative: fix segfault on empty trajectory (#595)
Browse files Browse the repository at this point in the history
Check that at least one robot state exists in the robot trajectory before accessing it.

Signed-off-by: Paul Gesel <[email protected]>
  • Loading branch information
pac48 authored Jul 16, 2024
1 parent 2e9a223 commit 60ccd74
Showing 1 changed file with 3 additions and 2 deletions.
5 changes: 3 additions & 2 deletions core/src/stages/move_relative.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -296,7 +296,8 @@ bool MoveRelative::compute(const InterfaceState& state, planning_scene::Planning
if (!success)
comment = result.message;

if (robot_trajectory) { // the following requires a robot_trajectory returned from planning
if (robot_trajectory && robot_trajectory->getWayPointCount() > 0) { // the following requires a robot_trajectory
// returned from planning
moveit::core::RobotStatePtr& reached_state = robot_trajectory->getLastWayPointPtr();
reached_state->updateLinkTransforms();
const Eigen::Isometry3d& reached_pose = reached_state->getGlobalLinkTransform(link) * offset;
Expand Down Expand Up @@ -331,7 +332,7 @@ bool MoveRelative::compute(const InterfaceState& state, planning_scene::Planning
}

// store result
if (robot_trajectory) {
if (robot_trajectory && robot_trajectory->getWayPointCount() > 0) {
scene->setCurrentState(robot_trajectory->getLastWayPoint());
if (dir == Interface::BACKWARD)
robot_trajectory->reverse();
Expand Down

0 comments on commit 60ccd74

Please sign in to comment.