Skip to content

Commit

Permalink
improve documentation in Fallbacks demo
Browse files Browse the repository at this point in the history
  • Loading branch information
v4hn committed Oct 10, 2023
1 parent fc42db4 commit b543a67
Showing 1 changed file with 13 additions and 8 deletions.
21 changes: 13 additions & 8 deletions demo/src/fallbacks_move_to.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,13 @@ constexpr double TAU = 2 * M_PI;

using namespace moveit::task_constructor;

/** CurrentState -> Fallbacks( MoveTo<CartesianPath>, MoveTo<PTP>, MoveTo<OMPL> )*/
/** Alternatives( 3 * FixedState with different states ) -> Fallbacks( MoveTo<CartesianPath>, MoveTo<PTP>, MoveTo<OMPL>
* )
*
* This task demonstrates how to use the Fallbacks stage to try different planning approaches in propagator.
* Note that the initial states are all different, so this task does not describe any real-world scenario (where all
* plans should start from the same initial state for execution).
*/
int main(int argc, char** argv) {
ros::init(argc, argv, "mtc_tutorial");

Expand All @@ -22,6 +28,7 @@ int main(int argc, char** argv) {

// setup Task
Task t;
t.setName("fallback strategies in MoveTo");
t.loadRobotModel();
const moveit::core::RobotModelConstPtr robot{ t.getRobotModel() };

Expand All @@ -39,11 +46,11 @@ int main(int argc, char** argv) {

const auto rrtconnect = []() {
auto pp{ std::make_shared<solvers::PipelinePlanner>("ompl") };
pp->setPlannerId("RRTConnectkConfigDefault");
pp->setPlannerId("RRTConnect");
return pp;
}();

// target state for Task
// target end state for all Task plans
std::map<std::string, double> target_state;
robot->getJointModelGroup("panda_arm")->getVariableDefaultPositions("ready", target_state);
target_state["panda_joint1"] = +TAU / 8;
Expand All @@ -56,15 +63,15 @@ int main(int argc, char** argv) {

{
// can reach target with Cartesian motion
auto fixed{ std::make_unique<stages::FixedState>("current state") };
auto fixed{ std::make_unique<stages::FixedState>("close to target state in workspace") };
auto scene{ initial_scene->diff() };
scene->getCurrentStateNonConst().setVariablePositions({ { "panda_joint1", -TAU / 8 } });
fixed->setState(scene);
initial_alternatives->add(std::move(fixed));
}
{
// Cartesian motion to target is impossible, but PTP is collision-free
auto fixed{ std::make_unique<stages::FixedState>("current state") };
auto fixed{ std::make_unique<stages::FixedState>("directly reachable without collision") };
auto scene{ initial_scene->diff() };
scene->getCurrentStateNonConst().setVariablePositions({
{ "panda_joint1", +TAU / 8 },
Expand All @@ -75,7 +82,7 @@ int main(int argc, char** argv) {
}
{
// Cartesian and PTP motion to target would be in collision
auto fixed = std::make_unique<stages::FixedState>("current state");
auto fixed{ std::make_unique<stages::FixedState>("getting to target requires collision avoidance") };
auto scene{ initial_scene->diff() };
scene->getCurrentStateNonConst().setVariablePositions({ { "panda_joint1", -TAU / 8 } });
scene->processCollisionObjectMsg([]() {
Expand Down Expand Up @@ -122,8 +129,6 @@ int main(int argc, char** argv) {
t.add(std::move(fallbacks));

try {
t.init();
std::cout << t << std::endl;
t.plan();
} catch (const InitStageException& e) {
std::cout << e << std::endl;
Expand Down

0 comments on commit b543a67

Please sign in to comment.