Skip to content

Commit 911bc67

Browse files
GenerateGraspPose: Expose rotation_axis as property (moveit#535)
1 parent 5720b83 commit 911bc67

File tree

2 files changed

+5
-2
lines changed

2 files changed

+5
-2
lines changed

core/include/moveit/task_constructor/stages/generate_grasp_pose.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -55,6 +55,7 @@ class GenerateGraspPose : public GeneratePose
5555
void setEndEffector(const std::string& eef) { setProperty("eef", eef); }
5656
void setObject(const std::string& object) { setProperty("object", object); }
5757
void setAngleDelta(double delta) { setProperty("angle_delta", delta); }
58+
void setRotationAxis(const Eigen::Vector3d& axis) { setProperty("rotation_axis", axis); }
5859

5960
void setPreGraspPose(const std::string& pregrasp) { properties().set("pregrasp", pregrasp); }
6061
void setPreGraspPose(const moveit_msgs::RobotState& pregrasp) { properties().set("pregrasp", pregrasp); }

core/src/stages/generate_grasp_pose.cpp

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -54,6 +54,7 @@ GenerateGraspPose::GenerateGraspPose(const std::string& name) : GeneratePose(nam
5454
p.declare<std::string>("eef", "name of end-effector");
5555
p.declare<std::string>("object");
5656
p.declare<double>("angle_delta", 0.1, "angular steps (rad)");
57+
p.declare<Eigen::Vector3d>("rotation_axis", Eigen::Vector3d::UnitZ(), "rotate object pose about given axis");
5758

5859
p.declare<boost::any>("pregrasp", "pregrasp posture");
5960
p.declare<boost::any>("grasp", "grasp posture");
@@ -160,11 +161,12 @@ void GenerateGraspPose::compute() {
160161

161162
geometry_msgs::PoseStamped target_pose_msg;
162163
target_pose_msg.header.frame_id = props.get<std::string>("object");
164+
Eigen::Vector3d rotation_axis = props.get<Eigen::Vector3d>("rotation_axis");
163165

164166
double current_angle = 0.0;
165167
while (current_angle < 2. * M_PI && current_angle > -2. * M_PI) {
166-
// rotate object pose about z-axis
167-
Eigen::Isometry3d target_pose(Eigen::AngleAxisd(current_angle, Eigen::Vector3d::UnitZ()));
168+
// rotate object pose about axis
169+
Eigen::Isometry3d target_pose(Eigen::AngleAxisd(current_angle, rotation_axis));
168170
current_angle += props.get<double>("angle_delta");
169171

170172
InterfaceState state(scene);

0 commit comments

Comments
 (0)