18 int main(
int argc, 
char **argv)
 
   24     auto fetch = std::make_shared<FetchRobot>();
 
   29     RBX_INFO(
"RViz Initialized! Press enter to continue (after your RViz is setup)...");
 
   36     auto planner = std::make_shared<darts::DARTPlanner>(
fetch);
 
   40     fetch->setGroupState(
GROUP, {0.05, 1.32, 1.40, -0.2, 1.72, 0.0, 1.66, 0.0});  
 
   43     fetch->setGroupState(
GROUP, {0.265, 0.501, 1.281, -2.272, 2.243, -2.774, 0.976, -2.007});  
 
   50     if (res.
error_code_.val != moveit_msgs::MoveItErrorCodes::SUCCESS)
 
RVIZ visualization helper. See Live Visualization with RViz for more information.
void updateTrajectory(const planning_interface::MotionPlanResponse &response)
Updates the trajectory being visualized.
A helper class to build motion planning requests for a robowflex::Planner.
bool setConfig(const std::string &requested_config)
Set the planning configuration to use for the motion planning request. Attempts to match requested_co...
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
#define RBX_INFO(fmt,...)
Output a info logging message.
Main namespace. Contains all library classes and functions.
Functions for loading and animating scenes in Blender.
moveit_msgs::MoveItErrorCodes error_code_