Skip to content

Commit

Permalink
Silent "empty quaternion" warning from poseMsgToEigen() (#3435)
Browse files Browse the repository at this point in the history
  • Loading branch information
rhaschke committed May 28, 2023
1 parent 55d2019 commit bc81091
Showing 1 changed file with 8 additions and 8 deletions.
16 changes: 8 additions & 8 deletions moveit_core/planning_scene/src/planning_scene.cpp
Expand Up @@ -1755,15 +1755,15 @@ bool PlanningScene::shapesAndPosesFromCollisionObjectMessage(const moveit_msgs::
shapes.reserve(num_shapes);
shape_poses.reserve(num_shapes);

PlanningScene::poseMsgToEigen(object.pose, object_pose);

bool switch_object_pose_and_shape_pose = false;
if (num_shapes == 1)
if (moveit::core::isEmpty(object.pose))
{
switch_object_pose_and_shape_pose = true; // If the object pose is not set but the shape pose is,
// use the shape's pose as the object pose.
}
if (num_shapes == 1 && moveit::core::isEmpty(object.pose))
{
// If the object pose is not set but the shape pose is, use the shape's pose as the object pose.
switch_object_pose_and_shape_pose = true;
object_pose.setIdentity();
}
else
PlanningScene::poseMsgToEigen(object.pose, object_pose);

auto append = [&object_pose, &shapes, &shape_poses,
&switch_object_pose_and_shape_pose](shapes::Shape* s, const geometry_msgs::Pose& pose_msg) {
Expand Down

0 comments on commit bc81091

Please sign in to comment.