Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fixed pose bug #282

Merged
merged 6 commits into from
Apr 11, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 6 additions & 0 deletions robowflex_library/src/scene.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -272,7 +272,13 @@ RobotPose Scene::getObjectPose(const std::string &name) const
const auto &world = scene_->getWorldNonConst();
const auto &obj = world->getObject(name);
if (obj)
{
#if ROBOWFLEX_MOVEIT_VERSION >= ROBOWFLEX_MOVEIT_VERSION_COMPUTE(1, 1, 6)
return obj->pose_ * obj->shape_poses_[0];
#else
return obj->shape_poses_[0];
#endif
}

return RobotPose::Identity();
}
Expand Down
35 changes: 35 additions & 0 deletions robowflex_library/src/yaml.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@

#include <robowflex_library/geometry.h>
#include <robowflex_library/io.h>
#include <robowflex_library/tf.h>
#include <robowflex_library/io/yaml.h>
#include <robowflex_library/macros.h>
#include <robowflex_library/yaml.h>
Expand Down Expand Up @@ -834,6 +835,10 @@ namespace YAML

node["id"] = rhs.id;

#if ROBOWFLEX_MOVEIT_VERSION >= ROBOWFLEX_MOVEIT_VERSION_COMPUTE(1, 1, 6)
node["pose"] = rhs.pose;
#endif

if (!rhs.type.key.empty())
node["type"] = rhs.type;

Expand Down Expand Up @@ -877,6 +882,8 @@ namespace YAML

bool convert<moveit_msgs::CollisionObject>::decode(const Node &node, moveit_msgs::CollisionObject &rhs)
{
RobotPose pose = TF::identity();
geometry_msgs::Pose pose_msg = TF::poseEigenToMsg(pose);
rhs = moveit_msgs::CollisionObject();

if (IO::isNode(node["header"]))
Expand All @@ -887,25 +894,53 @@ namespace YAML
if (IO::isNode(node["id"]))
rhs.id = node["id"].as<std::string>();

if (IO::isNode(node["pose"]))
{
pose_msg = node["pose"].as<geometry_msgs::Pose>();
pose = TF::poseMsgToEigen(pose_msg);
}

#if ROBOWFLEX_MOVEIT_VERSION >= ROBOWFLEX_MOVEIT_VERSION_COMPUTE(1, 1, 6)
rhs.pose = pose_msg;
#endif

if (IO::isNode(node["type"]))
rhs.type = node["type"].as<object_recognition_msgs::ObjectType>();

if (IO::isNode(node["primitives"]))
{
rhs.primitives = node["primitives"].as<std::vector<shape_msgs::SolidPrimitive>>();
rhs.primitive_poses = node["primitive_poses"].as<std::vector<geometry_msgs::Pose>>();

// If loading a newer format, add pose to include offset
#if ROBOWFLEX_MOVEIT_VERSION < ROBOWFLEX_MOVEIT_VERSION_COMPUTE(1, 1, 6)
for (auto &primitive_pose : rhs.primitive_poses)
primitive_pose = TF::poseEigenToMsg(pose * TF::poseMsgToEigen(primitive_pose));
#endif
}

if (IO::isNode(node["meshes"]))
{
rhs.meshes = node["meshes"].as<std::vector<shape_msgs::Mesh>>();
rhs.mesh_poses = node["mesh_poses"].as<std::vector<geometry_msgs::Pose>>();

// If loading a newer format, add pose to include offset
#if ROBOWFLEX_MOVEIT_VERSION < ROBOWFLEX_MOVEIT_VERSION_COMPUTE(1, 1, 6)
for (auto &mesh_pose : rhs.mesh_poses)
mesh_pose = TF::poseEigenToMsg(pose * TF::poseMsgToEigen(mesh_pose));
#endif
}

if (IO::isNode(node["planes"]))
{
rhs.planes = node["planes"].as<std::vector<shape_msgs::Plane>>();
rhs.plane_poses = node["plane_poses"].as<std::vector<geometry_msgs::Pose>>();

// If loading a newer format, add pose to include offset
#if ROBOWFLEX_MOVEIT_VERSION < ROBOWFLEX_MOVEIT_VERSION_COMPUTE(1, 1, 6)
for (auto &plane_pose : rhs.plane_poses)
plane_pose = TF::poseEigenToMsg(pose * TF::poseMsgToEigen(plane_pose));
#endif
}

if (IO::isNode(node["operation"]))
Expand Down