Utility functions for planning and execution routines to control the ShadowHand.
More...
|
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) |
|
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"
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_pubs | The list of controller publishers for execution |
plan | The plan to be executed |
- Returns
- Execution success or failure
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Execute plan for a given Finger asynchronously, where multiple Fingers can be executed simultaneously.
- Parameters
-
finger | The Finger whose plan is to be executed |
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_interface | The MoveGroup to generate pose for |
frame_name | The 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
-
finger | The Finger object whose joints are to be controlled |
targetJointAngles | The 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
-
options | shadow_planning::PlanningOptions object for computing the plan |
move_group_interface | The MoveGroup for which to plan |
reference_frame | The frame of reference for planning |
plan | The reference to the plan, which will be populated |
joint_targets | Map 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
-
options | The shadow_planning::PlanningOptions object for computing the plan |
move_group_interface | The MoveGroup for which to plan |
target_name | The named target |
plan | The reference to the plan, which will be populated |
- Returns
- Planning success or failure boolean
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
-
options | The shadow_planning::PlanningOptions object for computing the plan |
move_group_interface | The MoveGroup for which to plan |
target_pose | The target pose |
reference_frame | The frame of reference for planning |
plan | The reference to the plan, which will be populated |
end_effector_name | The name of the end-effector for which plan is computed |
- Returns
- Planning success or failure boolean