mirror of
https://github.com/moveit/moveit_task_constructor.git
synced 2025-11-04 14:49:57 +08:00
first sketch of the graph design
+ skeleton of a first node "current_state" + vision of a test application
This commit is contained in:
parent
e2b3cdb27d
commit
bd67649fd2
@ -7,6 +7,28 @@ find_package(catkin REQUIRED)
|
||||
find_package(moveit_core REQUIRED)
|
||||
|
||||
catkin_package(
|
||||
INCLUDE_DIRS include
|
||||
)
|
||||
|
||||
add_executable(test_plan_pick src/test_plan_pick.cpp)
|
||||
include_directories(
|
||||
include
|
||||
${moveit_core_INCLUDE_DIRS}
|
||||
)
|
||||
|
||||
add_compile_options(-std=c++14)
|
||||
|
||||
add_library(${PROJECT_NAME}_subtasks
|
||||
src/subtasks/move.cpp
|
||||
src/subtasks/current_state.cpp
|
||||
)
|
||||
|
||||
add_library(${PROJECT_NAME}
|
||||
src/subtask.cpp
|
||||
src/task.cpp
|
||||
)
|
||||
|
||||
add_executable(test_plan_current_state src/test/test_plan_current_state.cpp)
|
||||
target_link_libraries(test_plan_current_state ${PROJECT_NAME}_subtasks ${PROJECT_NAME})
|
||||
|
||||
add_executable(plan_pick src/plan_pick.cpp)
|
||||
target_link_libraries(plan_pick ${PROJECT_NAME}_subtasks ${PROJECT_NAME})
|
||||
|
||||
24
include/moveit_task_constructor/storage.h
Normal file
24
include/moveit_task_constructor/storage.h
Normal file
@ -0,0 +1,24 @@
|
||||
// copyright Michael 'v4hn' Goerner @ 2017
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <moveit/planning_scene/planning_scene.h>
|
||||
|
||||
namespace moveit::task_constructor {
|
||||
|
||||
MOVEIT_CLASS_FORWARD(SubTrajectory);
|
||||
MOVEIT_CLASS_FORWARD(InterfaceState);
|
||||
|
||||
struct SubTrajectory {
|
||||
robot_trajectory::RobotTrajectoryPtr trajectory;
|
||||
std::vector<InterfaceState*> next;
|
||||
std::vector<InterfaceState*> prev;
|
||||
};
|
||||
|
||||
struct InterfaceState {
|
||||
SubTrajectory* connection;
|
||||
|
||||
planning_scene::PlanningSceneConstPtr state;
|
||||
};
|
||||
|
||||
}
|
||||
45
include/moveit_task_constructor/subtask.h
Normal file
45
include/moveit_task_constructor/subtask.h
Normal file
@ -0,0 +1,45 @@
|
||||
// copyright Michael 'v4hn' Goerner @ 2017
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <moveit_task_constructor/storage.h>
|
||||
|
||||
#include <moveit/macros/class_forward.h>
|
||||
#include <moveit/planning_scene/planning_scene.h>
|
||||
|
||||
#include <vector>
|
||||
#include <list>
|
||||
|
||||
namespace moveit::task_constructor {
|
||||
|
||||
|
||||
MOVEIT_CLASS_FORWARD(SubTask);
|
||||
|
||||
class SubTask {
|
||||
public:
|
||||
SubTask(std::string name);
|
||||
|
||||
virtual bool canCompute() = 0;
|
||||
virtual bool compute() = 0;
|
||||
|
||||
const std::vector<InterfaceState>& getOut();
|
||||
const std::vector<InterfaceState>& getIn();
|
||||
const std::list<SubTrajectory>& getTrajectories();
|
||||
|
||||
void addPredecessor(SubTaskConstPtr);
|
||||
void addSuccessor(SubTaskConstPtr);
|
||||
|
||||
protected:
|
||||
const std::string name_;
|
||||
|
||||
// maintain raw pointers to predecessors to avoid pointer circles
|
||||
std::vector<const SubTask*> predecessors_;
|
||||
std::vector<SubTaskConstPtr> successors_;
|
||||
|
||||
std::list<SubTrajectory> trajectories_;
|
||||
|
||||
std::shared_ptr< std::vector<InterfaceState> > ins_;
|
||||
std::shared_ptr< std::vector<InterfaceState> > outs_;
|
||||
};
|
||||
|
||||
}
|
||||
18
include/moveit_task_constructor/subtasks/current_state.h
Normal file
18
include/moveit_task_constructor/subtasks/current_state.h
Normal file
@ -0,0 +1,18 @@
|
||||
// copyright Michael 'v4hn' Goerner @ 2017
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <moveit_task_constructor/subtask.h>
|
||||
|
||||
namespace moveit::task_constructor::subtasks {
|
||||
|
||||
class CurrentState : public SubTask {
|
||||
public:
|
||||
using SubTask::SubTask;
|
||||
|
||||
virtual bool canCompute();
|
||||
|
||||
virtual bool compute();
|
||||
};
|
||||
|
||||
}
|
||||
27
include/moveit_task_constructor/task.h
Normal file
27
include/moveit_task_constructor/task.h
Normal file
@ -0,0 +1,27 @@
|
||||
// copyright Michael 'v4hn' Goerner @ 2017
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <moveit/macros/class_forward.h>
|
||||
|
||||
#include <vector>
|
||||
|
||||
namespace moveit::task_constructor {
|
||||
|
||||
MOVEIT_CLASS_FORWARD(SubTask);
|
||||
|
||||
MOVEIT_CLASS_FORWARD(Task);
|
||||
class Task {
|
||||
public:
|
||||
Task();
|
||||
|
||||
void addStart( SubTaskPtr );
|
||||
void addAfter( SubTaskPtr );
|
||||
|
||||
bool plan();
|
||||
|
||||
protected:
|
||||
std::vector<SubTaskPtr> subtasks_;
|
||||
};
|
||||
|
||||
}
|
||||
59
src/plan_pick.cpp
Normal file
59
src/plan_pick.cpp
Normal file
@ -0,0 +1,59 @@
|
||||
#include <moveit_task_constructor/task.h>
|
||||
#include <moveit_task_constructor/subtask.h>
|
||||
|
||||
#include <moveit_task_constructor/subtasks/current_state.h>
|
||||
|
||||
using namespace moveit::task_constructor;
|
||||
|
||||
int main(){
|
||||
/*
|
||||
Task t;
|
||||
|
||||
t.addStart( std::make_shared<subtask::CurrentState>("current state") );
|
||||
|
||||
{
|
||||
auto move= std::make_shared<subtask::Gripper>("open gripper");
|
||||
move->setGroup("gripper");
|
||||
move->setTo("open");
|
||||
t.addAfter(move);
|
||||
}
|
||||
|
||||
{
|
||||
auto move= std::make_shared<subtask::Move>("move to pre-grasp");
|
||||
move->setGroup("arm");
|
||||
move->setPlannerId("RRTConnectkConfigDefault");
|
||||
move->setPlanningTime(5.0);
|
||||
t.addAfter(move);
|
||||
}
|
||||
|
||||
{
|
||||
auto move= std::make_shared<subtask::CartesianPositionMotion>("proceed to grasp pose");
|
||||
move->minMaxDistance(3.0, 10.0);
|
||||
move->towards("object", 0.0, 0.0, 0.0);
|
||||
t.addAfter(move);
|
||||
}
|
||||
|
||||
{
|
||||
auto grasps= std::make_shared<GenerateGraspPose>("generate grasp pose");
|
||||
}
|
||||
|
||||
{
|
||||
auto move= std::make_shared<subtask::Gripper>("grasp");
|
||||
move->setGroup("gripper");
|
||||
move->setTo("closed");
|
||||
move->graspObject("object");
|
||||
t.addAfter(move);
|
||||
}
|
||||
|
||||
{
|
||||
auto move= std::make_shared<subtask::CartesianPositionMotion>("Lift Object");
|
||||
move->setGroup("arm");
|
||||
move->minMaxDistance(3.0, 5.0);
|
||||
move->along("world", 0.0, 0.0, 1.0);
|
||||
t.addAfter(move);
|
||||
}
|
||||
|
||||
t.plan();
|
||||
*/
|
||||
return 0;
|
||||
}
|
||||
30
src/subtask.cpp
Normal file
30
src/subtask.cpp
Normal file
@ -0,0 +1,30 @@
|
||||
#include <moveit_task_constructor/subtask.h>
|
||||
|
||||
moveit::task_constructor::SubTask::SubTask(std::string name)
|
||||
: name_(name),
|
||||
ins_(new std::vector<InterfaceState>),
|
||||
outs_(new std::vector<InterfaceState>)
|
||||
{};
|
||||
|
||||
void moveit::task_constructor::SubTask::addPredecessor(SubTaskConstPtr prev_task){
|
||||
predecessors_.push_back( prev_task.get() );
|
||||
}
|
||||
|
||||
void moveit::task_constructor::SubTask::addSuccessor(SubTaskConstPtr next_task){
|
||||
successors_.push_back( next_task );
|
||||
}
|
||||
|
||||
const std::vector<moveit::task_constructor::InterfaceState>&
|
||||
moveit::task_constructor::SubTask::getIn(){
|
||||
return *ins_;
|
||||
}
|
||||
|
||||
const std::vector<moveit::task_constructor::InterfaceState>&
|
||||
moveit::task_constructor::SubTask::getOut(){
|
||||
return *outs_;
|
||||
}
|
||||
|
||||
const std::list<moveit::task_constructor::SubTrajectory>&
|
||||
moveit::task_constructor::SubTask::getTrajectories(){
|
||||
return trajectories_;
|
||||
}
|
||||
11
src/subtasks/current_state.cpp
Normal file
11
src/subtasks/current_state.cpp
Normal file
@ -0,0 +1,11 @@
|
||||
#include <moveit_task_constructor/subtasks/current_state.h>
|
||||
|
||||
bool
|
||||
moveit::task_constructor::subtasks::CurrentState::canCompute(){
|
||||
return true;
|
||||
}
|
||||
|
||||
bool
|
||||
moveit::task_constructor::subtasks::CurrentState::compute(){
|
||||
return false;
|
||||
}
|
||||
0
src/subtasks/move.cpp
Normal file
0
src/subtasks/move.cpp
Normal file
20
src/task.cpp
Normal file
20
src/task.cpp
Normal file
@ -0,0 +1,20 @@
|
||||
#include <moveit_task_constructor/task.h>
|
||||
#include <moveit_task_constructor/subtask.h>
|
||||
|
||||
moveit::task_constructor::Task::Task()
|
||||
{}
|
||||
|
||||
void moveit::task_constructor::Task::addStart( SubTaskPtr subtask ){
|
||||
subtasks_.clear();
|
||||
subtasks_.push_back( subtask );
|
||||
}
|
||||
|
||||
void moveit::task_constructor::Task::addAfter( SubTaskPtr subtask ){
|
||||
subtask->addPredecessor( subtasks_.back() );
|
||||
subtasks_.back()->addSuccessor( subtask );
|
||||
subtasks_.push_back( subtask );
|
||||
}
|
||||
|
||||
bool moveit::task_constructor::Task::plan(){
|
||||
return false;
|
||||
}
|
||||
17
src/test/test_plan_current_state.cpp
Normal file
17
src/test/test_plan_current_state.cpp
Normal file
@ -0,0 +1,17 @@
|
||||
#include <moveit_task_constructor/task.h>
|
||||
#include <moveit_task_constructor/subtask.h>
|
||||
|
||||
#include <moveit_task_constructor/subtasks/current_state.h>
|
||||
|
||||
using namespace moveit::task_constructor;
|
||||
|
||||
int main(){
|
||||
|
||||
Task t;
|
||||
|
||||
t.addStart( std::make_shared<subtasks::CurrentState>("current state") );
|
||||
|
||||
t.plan();
|
||||
|
||||
return 0;
|
||||
}
|
||||
@ -1,3 +0,0 @@
|
||||
int main(){
|
||||
return 0;
|
||||
}
|
||||
Loading…
Reference in New Issue
Block a user