环境:Ubuntu16.04+ROS Kinetic
STOMP(随机轨迹优化运动规划算法)是基于PI^2算法的进行优化的运动规划器。它可以完成机器人手臂运动轨迹的平滑规划,同时避开障碍物和优化约束。 该算法不需要梯度,因此可以优化成本函数中的任意项,如电机工作。
注意:STOMP只能用于机械臂关节空间的路径规划,不能用于空间末端运动轨迹的规划。
1、编译industrial_moveit源码
cd ~/catkin_ws/src
git clone https://github.com/ros-industrial/industrial_moveit.git
删除下面文件
2、在config包的launch目录下新建文件stomp_planning_pipeline.launch.xml,内容如下,
3、修改move_group.launch文件
4、在config包的config目录下新建文件stomp_planning.yaml,内容如下,groupname为规划组名字,相关参数需根据机械臂进行修改。
stomp/groupname:
group_name: groupname
optimization:
num_timesteps: 60
num_iterations: 40
num_iterations_after_valid: 0
num_rollouts: 30
max_rollouts: 30
initialization_method: 1 #[1 : LINEAR_INTERPOLATION, 2 : CUBIC_POLYNOMIAL, 3 : MININUM_CONTROL_COST
control_cost_weight: 0.0
task:
noise_generator:
- class: stomp_moveit/NormalDistributionSampling
stddev: [0.05, 0.8, 1.0, 0.8, 0.4, 0.4, 0.4]
cost_functions:
- class: stomp_moveit/CollisionCheck
collision_penalty: 1.0
cost_weight: 1.0
kernel_window_percentage: 0.2
longest_valid_joint_move: 0.05
noisy_filters:
- class: stomp_moveit/JointLimits
lock_start: True
lock_goal: True
- class: stomp_moveit/MultiTrajectoryVisualization
line_width: 0.02
rgb: [255, 255, 0]
marker_array_topic: stomp_trajectories
marker_namespace: noisy
update_filters:
- class: stomp_moveit/PolynomialSmoother
poly_order: 6
- class: stomp_moveit/TrajectoryVisualization
line_width: 0.05
rgb: [0, 191, 255]
error_rgb: [255, 0, 0]
publish_intermediate: True
marker_topic: stomp_trajectory
marker_namespace: optimized
部分参数说明
Optimization Parameters:(优化设置)
Noise Generator Parameters:(噪声设置)
Cost Function Parameters:(成本设置)
Update Filter parameters:
参数设置例子
/**
@page stomp_plugins_examples STOMP Plugins Examples
@tableofcontents
@section stomp_plugins STOMP Plugins
@subsection cost_functions_plugins Cost Function Plugins
- @ref tool_goal_pose_example
@subsection noise_generators Noise Generator Plugins
- @ref goal_guided_mult_gaussian_example
@subsection constrained_cart_goal Update Filter Plugins
- @ref constrained_cart_goal_example
*/
/**
@page tool_goal_pose_example Tool Goal Pose
Evaluates the cost of the goal pose by determining how far it is from the underconstrained task manifold. The parameters
are as follow:
@code
cost_functions:
- class: stomp_moveit/ToolGoalPose
constrained_dofs: [1, 1, 1, 1, 1, 0]
position_error_range: [0.01, 0.1] #[min, max]
orientation_error_range: [0.01, 0.1] #[min, max]
position_cost_weight: 0.5
orientation_cost_weight: 0.5
@endcode
- class: The class name.
- constrained_dofs: Indicates which cartesians DOF are fully constrained (1) or unconstrained (0). This vector is of the form
[x y z rx ry rz] where each entry can only take a value of 0 or 1.
- position_error_range: Used in scaling the position error from 0 to 1. Any error less than this range is set to
a cost of 0 and errors above this range are set to 1.
- orientation_error_range: Used in scaling the orientation error from 0 to 1. Any error less than this range is set to
a cost of 0 and errors above this range are set to 1.
- position_cost_weight: Factor applied to the position error cost. The total cost = pos_cost * pos_weight + orient_cost * orient_weight
- orientation_cost_weight: Factor applied to the orientation error cost. The total cost = pos_cost * pos_weight + orient_cost * orient_weight
*/
/**
@page goal_guided_mult_gaussian_example Goal Guided Multivariate Gaussian
Generates noise that is applied onto the trajectory while keeping the goal pose within the task manifold. The parameters are
as follows:
@code
noise_generator:
- class: stomp_moveit/GoalGuidedMultivariateGaussian
stddev: [0.1, 0.05, 0.1, 0.05, 0.05, 0.05, 0.05]
goal_stddev: [0.0, 0.0, 0.0, 0.0, 0.0, 2.0]
constrained_dofs: [1, 1, 1, 1, 1, 0]
@endcode
- class: The class name.
- stddev: The amplitude of the noise applied onto each joint.
- goal_stddev: The amplitude of the noise applied onto each cartesian DOF at the goal. The array has the following
form [px, py, pz, rx, ry, rz].
- constrained_dofs: Indicates which cartesians DOF are fully constrained (1) or unconstrained (0). This vector is of the form
[x y z rx ry rz] where each entry can only take a value of 0 or 1.
*/
/**
@page constrained_cart_goal_example Constrained Cartesian Goal
Modifies the trajectory update such that the goal of the updated trajectory is within the task manifold
@code
update_filters:
- class: stomp_moveit/ConstrainedCartesianGoal
constrained_dofs: [1, 1, 1, 1, 1, 0]
cartesian_convergence: [0.005, 0.005, 0.005, 0.01, 0.01, 1.00]
joint_update_rates: [0.5, 0.5, 0.5, 0.5, 0.5, 0.5, 0.5]
max_ik_iterations: 100
@endcode
- class: The class name.
- constrained_dofs: Indicates which cartesians DOF are fully constrained (1) or unconstrained (0). This vector is of the form
[x y z rx ry rz] where each entry can only take a value of 0 or 1.
- cartesian_convergence: A vector of convergence values for each cartesian DOF [vx vy vz wx wy wz].
- joint_update_rates: The rates at which to update the joints during numerical ik computations.
- max_ik_iterations: Limit on the number of iterations allowed for numerical ik computations.
*/
因运动学规划算法STOMP只能用于关节空间的运动规划,因此在使用时需先求取目标点的逆解,然后再通过STOMP进行初始状态到目标状态之间的运动规划。
group.setStartState(*group.getCurrentState());
// joint space goal
robot_model_loader::RobotModelLoader robot_model_loader(
"robot_description");
robot_model::RobotModelPtr robot_model_ptr =
robot_model_loader.getModel();
robot_state::RobotStatePtr robot_state_ptr(
group.getCurrentState()); // copy state
const robot_state::JointModelGroup *joint_model_group =
robot_model_ptr->getJointModelGroup(group.getName());
bool found_ik =
robot_state_ptr->setFromIK(joint_model_group, target_pose, 10, 1);
if (found_ik) {
std::vector jointValues;
robot_state_ptr->copyJointGroupPositions("hand", jointValues);
group.setJointValueTarget(jointValues);
moveit::planning_interface::MoveGroupInterface::Plan plan;
success = group.plan(plan);
ROS_INFO("Visualizing plan %s",
success == moveit_msgs::MoveItErrorCodes::SUCCESS ? "SUCCESS"
: "FAILED");
} else
ROS_INFO("setFromIK: FAILED");
参考
http://docs.ros.org/kinetic/api/moveit_tutorials/html/doc/stomp_planner/stomp_planner_tutorial.html
http://docs.ros.org/kinetic/api/moveit_tutorials/html/doc/stomp_planner/stomp_planner_tutorial.html
https://github.com/ros-industrial/industrial_moveit/issues/70
https://groups.google.com/forum/#!topic/swri-ros-pkg-dev/sNvFmkQsMtg