Skip to content

Commit

Permalink
adding a pre-configured pose and updating the dimensions for planning…
Browse files Browse the repository at this point in the history
… with external elements (#40)
  • Loading branch information
padhupradheep authored Feb 6, 2023
1 parent 6ec1924 commit cb23bc8
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 2 deletions.
8 changes: 8 additions & 0 deletions elite_moveit/config/ec66.srdf
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,14 @@
<joint name="joint5" value="-4.6169"/>
<joint name="joint6" value="-1.4233"/>
</group_state>
<group_state name="pre-sine" group="arm">
<joint name="joint1" value="0"/>
<joint name="joint2" value="-1.5448"/>
<joint name="joint3" value="1.57"/>
<joint name="joint4" value="-1.57"/>
<joint name="joint5" value="1.848"/>
<joint name="joint6" value="0.5712"/>
</group_state>
<!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. -->
<disable_collisions link1="base_link" link2="link1" reason="Adjacent"/>
<disable_collisions link1="base_link" link2="link2" reason="Never"/>
Expand Down
4 changes: 2 additions & 2 deletions neo_arm_tutorial/src/plan_with_external_elements.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,13 +43,13 @@ int main(int argc, char** argv)

/* A default pose */
geometry_msgs::msg::Pose pose;
pose.position.z = 0.03;
pose.position.z = 0.04;
pose.orientation.w = 1.0;

shape_msgs::msg::SolidPrimitive primitive;
primitive.type = primitive.CYLINDER;
primitive.dimensions.resize(2);
primitive.dimensions[0] = 0.042;
primitive.dimensions[0] = 0.05;
primitive.dimensions[1] = 0.08;

attached_object.object.primitives.push_back(primitive);
Expand Down

0 comments on commit cb23bc8

Please sign in to comment.