22 int main(
int argc,
char **argv)
28 auto fetch = std::make_shared<FetchRobot>();
29 fetch->initialize(
false);
35 auto planner = std::make_shared<TrajOptPlanner>(
fetch,
GROUP);
36 planner->initialize(
"torso_lift_link",
"gripper_link");
37 planner->options.num_waypoints = 3;
41 fetch->setGroupState(
GROUP, {0.201, 1.281, -2.272, 2.243, -2.774, 0.976, -2.007});
44 fetch->setGroupState(
GROUP, {1.301, 1.281, -2.272, 2.243, -2.774, 0.976, -2.007});
49 if (res.
error_code_.val != moveit_msgs::MoveItErrorCodes::SUCCESS)
56 trajectory->toYAMLFile(
"fetch_trajopt_path.yml");
A helper class to build motion planning requests for a robowflex::Planner.
void setStartConfiguration(const std::vector< double > &joints)
Set the start configuration from a vector joints. All joints are assumed to be specified and in the d...
planning_interface::MotionPlanRequest & getRequest()
Get a reference to the currently built motion planning request.
void setGoalConfiguration(const std::vector< double > &joints)
Set the goal configuration from a vector joints. All joints are assumed to be specified and in the de...
RAII-pattern for starting up ROS.
int main(int argc, char **argv)
static const std::string GROUP
Main namespace. Contains all library classes and functions.
Functions for loading and animating scenes in Blender.
moveit_msgs::MoveItErrorCodes error_code_
robot_trajectory::RobotTrajectoryPtr trajectory_
robot_trajectory::RobotTrajectory trajectory(rmodel,"right_arm")