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

WIP: Update tutorials to work with the new collision geometries of panda #566

Open
wants to merge 2 commits into
base: master
Choose a base branch
from
Open
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
Original file line number Diff line number Diff line change
Expand Up @@ -157,7 +157,8 @@ int main(int argc, char** argv)
{
// BEGIN_TUTORIAL
// The code starts with creating an interactive robot and a new planning scene.
InteractiveRobot interactive_robot("robot_description", "bullet_collision_tutorial/interactive_robot_state");
InteractiveRobot interactive_robot("ready", "robot_description",
"bullet_collision_tutorial/interactive_robot_state");
g_planning_scene = std::make_unique<planning_scene::PlanningScene>(interactive_robot.robotModel());

// Changing the collision detector to Bullet
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@
class InteractiveRobot
{
public:
InteractiveRobot(const std::string& robot_description = "robot_description",
InteractiveRobot(const std::string& start_pose, const std::string& robot_description = "robot_description",
const std::string& robot_topic = "interactive_robot_state",
const std::string& marker_topic = "interactive_robot_markers",
const std::string& imarker_topic = "interactive_robot_imarkers");
Expand Down
7 changes: 4 additions & 3 deletions doc/interactivity/src/interactive_robot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,8 +50,9 @@ const double InteractiveRobot::WORLD_BOX_SIZE_ = 0.15;
// minimum delay between calls to callback function
const ros::Duration InteractiveRobot::min_delay_(0.01);

InteractiveRobot::InteractiveRobot(const std::string& robot_description, const std::string& robot_topic,
const std::string& marker_topic, const std::string& imarker_topic)
InteractiveRobot::InteractiveRobot(const std::string& start_pose, const std::string& robot_description,
const std::string& robot_topic, const std::string& marker_topic,
const std::string& imarker_topic)
: user_data_(nullptr)
, nh_() // this node handle is used to create the publishers
// create publishers for markers and robot state
Expand Down Expand Up @@ -80,10 +81,10 @@ InteractiveRobot::InteractiveRobot(const std::string& robot_description, const s
ROS_ERROR("Could not get RobotState from Model");
throw RobotLoadException();
}
robot_state_->setToDefaultValues();

// Prepare to move the "panda_arm" group
group_ = robot_state_->getJointModelGroup("panda_arm");
robot_state_->setToDefaultValues(group_, start_pose);
std::string end_link = group_->getLinkModelNames().back();
desired_group_end_link_pose_ = robot_state_->getGlobalLinkTransform(end_link);

Expand Down
12 changes: 7 additions & 5 deletions doc/subframes/src/subframes_tutorial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -247,6 +247,7 @@ int main(int argc, char** argv)
att_coll_object.object.id = "cylinder";
att_coll_object.link_name = "panda_hand";
att_coll_object.object.operation = att_coll_object.object.ADD;
att_coll_object.touch_links = { att_coll_object.link_name };
ROS_INFO_STREAM("Attaching cylinder to robot.");
planning_scene_interface.applyAttachedCollisionObject(att_coll_object);
// END_SUB_TUTORIAL
Expand Down Expand Up @@ -319,7 +320,7 @@ int main(int argc, char** argv)
target_orientation.setRPY(0, 180.0 / 180.0 * M_PI, 90.0 / 180.0 * M_PI);
target_pose.pose.orientation = tf2::toMsg(target_orientation);
// To keep some distance to the box, we use a small offset:
target_pose.pose.position.z = 0.01;
target_pose.pose.position.z = 0.03;
showFrames(target_pose, "cylinder/tip");
moveToCartPose(target_pose, group, "cylinder/tip");
// END_SUB_TUTORIAL
Expand All @@ -332,7 +333,7 @@ int main(int argc, char** argv)
target_pose.header.frame_id = "box/top";
target_orientation.setRPY(180.0 / 180.0 * M_PI, 0, 90.0 / 180.0 * M_PI);
target_pose.pose.orientation = tf2::toMsg(target_orientation);
target_pose.pose.position.z = 0.01;
target_pose.pose.position.z = 0.03;
showFrames(target_pose, "cylinder/tip");
moveToCartPose(target_pose, group, "cylinder/tip");
}
Expand All @@ -343,7 +344,7 @@ int main(int argc, char** argv)
target_pose.header.frame_id = "box/corner_1";
target_orientation.setRPY(0, 180.0 / 180.0 * M_PI, 90.0 / 180.0 * M_PI);
target_pose.pose.orientation = tf2::toMsg(target_orientation);
target_pose.pose.position.z = 0.01;
target_pose.pose.position.z = 0.03;
showFrames(target_pose, "cylinder/tip");
moveToCartPose(target_pose, group, "cylinder/tip");
}
Expand All @@ -352,7 +353,7 @@ int main(int argc, char** argv)
target_pose.header.frame_id = "box/corner_2";
target_orientation.setRPY(0, 180.0 / 180.0 * M_PI, 90.0 / 180.0 * M_PI);
target_pose.pose.orientation = tf2::toMsg(target_orientation);
target_pose.pose.position.z = 0.01;
target_pose.pose.position.z = 0.03;
showFrames(target_pose, "cylinder/tip");
moveToCartPose(target_pose, group, "cylinder/tip");
}
Expand All @@ -361,7 +362,7 @@ int main(int argc, char** argv)
target_pose.header.frame_id = "box/side";
target_orientation.setRPY(0, 180.0 / 180.0 * M_PI, 90.0 / 180.0 * M_PI);
target_pose.pose.orientation = tf2::toMsg(target_orientation);
target_pose.pose.position.z = 0.01;
target_pose.pose.position.z = 0.05;
showFrames(target_pose, "cylinder/tip");
moveToCartPose(target_pose, group, "cylinder/tip");
}
Expand Down Expand Up @@ -421,6 +422,7 @@ int main(int argc, char** argv)
att_coll_object.object.id = "cylinder";
att_coll_object.link_name = "panda_hand";
att_coll_object.object.operation = att_coll_object.object.ADD;
att_coll_object.touch_links = { att_coll_object.link_name };
ROS_INFO_STREAM("Attaching cylinder to robot.");
planning_scene_interface.applyAttachedCollisionObject(att_coll_object);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -170,7 +170,7 @@ int main(int argc, char** argv)
// object as a wrapper that combines a robot_model with the cube and an interactive marker. We also
// create a :planning_scene:`PlanningScene` for collision checking. If you haven't already gone through the
// `planning scene tutorial <../planning_scene/planning_scene_tutorial.html>`_, you go through that first.
InteractiveRobot robot;
InteractiveRobot robot("ready");
/* Create a PlanningScene */
g_planning_scene = new planning_scene::PlanningScene(robot.robotModel());

Expand Down