30 int main(
int argc,
char **argv)
36 auto cob4 = std::make_shared<Cob4Robot>();
43 cob4->setGroupState(
BOTH_ARMS, {-1.14, -1.50, 0.34, -1.50, 0.43, -1.56, -1.20, 2.69, 1.70, -0.91, 1.50,
47 auto scene = std::make_shared<Scene>(cob4);
48 scene->fromYAMLFile(
"package://robowflex_library/yaml/test_cob4.yml");
54 RBX_INFO(
"Care-O-Bot4 with both_arms folded is visualized. Press enter to continue...");
58 auto planner = std::make_shared<OMPL::Cob4OMPLPipelinePlanner>(cob4);
59 planner->initialize();
66 const auto &goal_pose_right =
TF::createPoseQ(0.6, -0.26, 0.97, 1.0, 0.0, 0.0, 0.0);
67 const auto &goal_pose_left =
TF::createPoseQ(0.38, 0.26, 0.78, 0.0, 0.707, 0.0, 0.707);
73 RBX_INFO(
"Target IK poses are visualized. Press enter to continue...");
77 if (not cob4->setFromIK(query))
86 RBX_INFO(
"Solution to IK is visualized and set as goal for both_arms! Press enter to plan...");
90 request_both_arms.
setConfig(
"RRTConnect");
92 if (res.
error_code_.val != moveit_msgs::MoveItErrorCodes::SUCCESS)
99 auto both_arms_trajectory = std::make_shared<Trajectory>(res.
trajectory_);
100 cob4->setGroupState(
BOTH_ARMS, both_arms_trajectory->vectorize().
back());
104 RBX_INFO(
"Trajectory visualize. Press enter to exit.");
RVIZ visualization helper. See Live Visualization with RViz for more information.
void updateMarkers()
Displays the managed list of markers. Keeps track of whether markers have already been displayed and ...
void visualizeCurrentState()
Visualize the current state of the robot.
void updateScene(const SceneConstPtr &scene)
Updates the scene being visualized.
void updateTrajectory(const planning_interface::MotionPlanResponse &response)
Updates the trajectory being visualized.
void addTransformMarker(const std::string &name, const std::string &base_frame, const RobotPose &pose, double scale=1)
Add a transform marker to the managed list of markers. Displayed after an updateMarkers() call.
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 LEFT_EE
static const std::string LEFT_ARM
static const std::string BOTH_ARMS
static const std::string RIGHT_EE
static const std::string RIGHT_ARM
#define RBX_ERROR(fmt,...)
Output a error logging message.
#define RBX_INFO(fmt,...)
Output a info logging message.
RobotPose createPoseQ(double x, double y, double z, double W, double X, double Y, double Z)
Creates a robot pose from a linear component and a Quaternion.
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 IK Query options. IK queries in Robowflex consist of: a) A position specified by some geometric...