ShadowHandUtilityLibrary
Classes | Functions
shadow_planning Namespace Reference

Utility functions for planning and execution routines to control the ShadowHand. More...

Classes

struct  PlanningOptions
 Struct to set planning parameters for MoveIt planning. More...
 

Functions

geometry_msgs::Pose getRandomPose (moveit::planning_interface::MoveGroupInterface &move_group_interface, std::string &frame_name)
 Construct random target pose for a given planning group. More...
 
bool planToNamedTarget (shadow_planning::PlanningOptions &options, moveit::planning_interface::MoveGroupInterface &move_group_interface, std::string &target_name, moveit::planning_interface::MoveGroupInterface::Plan &plan)
 Construct plan to a given "named" target, these are obtained from predefined RViz names. More...
 
bool planToNamedTarget (shadow_finger::Finger &finger, std::string &target_name)
 
bool planToPoseTarget (shadow_planning::PlanningOptions &options, moveit::planning_interface::MoveGroupInterface &move_group_interface, geometry_msgs::Pose &target_pose, std::string &reference_frame, moveit::planning_interface::MoveGroupInterface::Plan &plan, std::string &end_effector_name)
 Construct plan to a given Pose target. More...
 
bool planToJointTargets (shadow_planning::PlanningOptions &options, moveit::planning_interface::MoveGroupInterface &move_group_interface, std::string &reference_frame, moveit::planning_interface::MoveGroupInterface::Plan &plan, std::map< std::string, double > &joint_targets)
 Construct plan to given Joint target. More...
 
void moveFingerJoints (shadow_finger::Finger &finger, std::vector< double > &targetJointAngles)
 Move all joints in fingers by given angle (in degrees). Directly use joint publishers to set target commands. More...
 
bool executePlan (std::vector< ros::Publisher > &controller_pubs, moveit::planning_interface::MoveGroupInterface::Plan &plan)
 Execute plan for a given plan given its list of controllers. More...
 
bool executePlan (shadow_finger::Finger &finger)
 
void executePlanAsync (shadow_finger::Finger &finger)
 Execute plan for a given Finger asynchronously, where multiple Fingers can be executed simultaneously. More...
 
void executePlanAsync (shadow_hand::Hand &hand)
 

Detailed Description

Utility functions for planning and execution routines to control the ShadowHand.

Contains PlanningOptions to set necessary parameters for planning.

shadow_planning.hpp "include/shadowlibs/shadow_planning.hpp"

shadow_planning_options.hpp "include/shadowlibs/shadow_planning_options.hpp"

Function Documentation

bool shadow_planning::executePlan ( std::vector< ros::Publisher > &  controller_pubs,
moveit::planning_interface::MoveGroupInterface::Plan &  plan 
)

Execute plan for a given plan given its list of controllers.

Parameters
controller_pubsThe list of controller publishers for execution
planThe plan to be executed
Returns
Execution success or failure
bool shadow_planning::executePlan ( shadow_finger::Finger finger)

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

void shadow_planning::executePlanAsync ( shadow_finger::Finger finger)

Execute plan for a given Finger asynchronously, where multiple Fingers can be executed simultaneously.

Parameters
fingerThe Finger whose plan is to be executed
void shadow_planning::executePlanAsync ( shadow_hand::Hand hand)

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

geometry_msgs::Pose shadow_planning::getRandomPose ( moveit::planning_interface::MoveGroupInterface &  move_group_interface,
std::string &  frame_name 
)

Construct random target pose for a given planning group.

Parameters
move_group_interfaceThe MoveGroup to generate pose for
frame_nameThe name of the reference frame
Returns
The generated random pose
void shadow_planning::moveFingerJoints ( shadow_finger::Finger finger,
std::vector< double > &  targetJointAngles 
)

Move all joints in fingers by given angle (in degrees). Directly use joint publishers to set target commands.

Parameters
fingerThe Finger object whose joints are to be controlled
targetJointAnglesThe target joints angles for each joint in finger
bool shadow_planning::planToJointTargets ( shadow_planning::PlanningOptions options,
moveit::planning_interface::MoveGroupInterface &  move_group_interface,
std::string &  reference_frame,
moveit::planning_interface::MoveGroupInterface::Plan &  plan,
std::map< std::string, double > &  joint_targets 
)

Construct plan to given Joint target.

Parameters
optionsshadow_planning::PlanningOptions object for computing the plan
move_group_interfaceThe MoveGroup for which to plan
reference_frameThe frame of reference for planning
planThe reference to the plan, which will be populated
joint_targetsMap from joint name to the target value
Returns
Planning success or failure boolean
bool shadow_planning::planToNamedTarget ( shadow_planning::PlanningOptions options,
moveit::planning_interface::MoveGroupInterface &  move_group_interface,
std::string &  target_name,
moveit::planning_interface::MoveGroupInterface::Plan &  plan 
)

Construct plan to a given "named" target, these are obtained from predefined RViz names.

Parameters
optionsThe shadow_planning::PlanningOptions object for computing the plan
move_group_interfaceThe MoveGroup for which to plan
target_nameThe named target
planThe reference to the plan, which will be populated
Returns
Planning success or failure boolean
bool shadow_planning::planToNamedTarget ( shadow_finger::Finger finger,
std::string &  target_name 
)

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

bool shadow_planning::planToPoseTarget ( shadow_planning::PlanningOptions options,
moveit::planning_interface::MoveGroupInterface &  move_group_interface,
geometry_msgs::Pose &  target_pose,
std::string &  reference_frame,
moveit::planning_interface::MoveGroupInterface::Plan &  plan,
std::string &  end_effector_name 
)

Construct plan to a given Pose target.

Parameters
optionsThe shadow_planning::PlanningOptions object for computing the plan
move_group_interfaceThe MoveGroup for which to plan
target_poseThe target pose
reference_frameThe frame of reference for planning
planThe reference to the plan, which will be populated
end_effector_nameThe name of the end-effector for which plan is computed
Returns
Planning success or failure boolean