Skip to content

Commit 9557290

Browse files
sjahrwyattreessea-bass
authored
Continuation of "Adding kinematics cost function tutorial #462" (#669)
Co-authored-by: Wyatt Rees <[email protected]> Co-authored-by: Sebastian Castro <[email protected]>
1 parent 300f53a commit 9557290

File tree

6 files changed

+347
-0
lines changed

6 files changed

+347
-0
lines changed

CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -62,6 +62,7 @@ add_subdirectory(doc/examples/planning_scene_ros_api)
6262
add_subdirectory(doc/examples/planning_scene)
6363
add_subdirectory(doc/examples/realtime_servo)
6464
add_subdirectory(doc/examples/robot_model_and_robot_state)
65+
add_subdirectory(doc/how_to_guides/kinematics_cost_function)
6566
add_subdirectory(doc/how_to_guides/parallel_planning)
6667
add_subdirectory(doc/how_to_guides/persistent_scenes_and_states)
6768
add_subdirectory(doc/how_to_guides/pilz_industrial_motion_planner)

doc/how_to_guides/how_to_guides.rst

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -11,6 +11,7 @@ Configuring and Using MoveIt
1111
.. toctree::
1212
:maxdepth: 1
1313

14+
kinematics_cost_function/kinematics_cost_function_tutorial
1415
moveit_configuration/moveit_configuration_tutorial
1516
pilz_industrial_motion_planner/pilz_industrial_motion_planner
1617
using_ompl_constrained_planning/ompl_constrained_planning
Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,13 @@
1+
add_executable(kinematics_cost_function_tutorial
2+
src/kinematics_cost_function_tutorial.cpp)
3+
target_include_directories(kinematics_cost_function_tutorial
4+
PUBLIC include)
5+
ament_target_dependencies(kinematics_cost_function_tutorial
6+
${THIS_PACKAGE_INCLUDE_DEPENDS})
7+
8+
install(TARGETS kinematics_cost_function_tutorial
9+
DESTINATION lib/${PROJECT_NAME}
10+
)
11+
install(DIRECTORY launch
12+
DESTINATION share/${PROJECT_NAME}
13+
)
Lines changed: 54 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,54 @@
1+
Kinematics Cost Functions
2+
==================================
3+
4+
When querying for IK solutions for a goal pose or for a cartesian path goal, we can specify *cost functions* that will be used
5+
to evaluate the fitness of solutions.
6+
7+
Getting Started
8+
---------------
9+
If you haven't already done so, make sure you've completed the steps in :doc:`Getting Started </doc/tutorials/getting_started/getting_started>`.
10+
11+
This tutorial also requires the use of `bio_ik <https://github.com/PickNikRobotics/bio_ik>`_ as the Inverse Kinematics plugin. First, clone the "ros2" branch of this repository into your workspace's **src** directory: ::
12+
13+
git clone -b ros2 https://github.com/PickNikRobotics/bio_ik.git
14+
15+
Then, change your kinematics plugin for the Panda robot by copying the following into moveit_resources/panda_moveit_config/config/kinematics.yaml within your workspace: ::
16+
17+
panda_arm:
18+
kinematics_solver: bio_ik/BioIKKinematicsPlugin
19+
kinematics_solver_search_resolution: 0.005
20+
kinematics_solver_timeout: 0.005
21+
kinematics_solver_attempts: 1
22+
mode: gd_c # use the gradient descent solver
23+
24+
After making these changes, rebuild your workspace: ::
25+
26+
colcon build --mixin release
27+
28+
Running the Code
29+
----------------
30+
Open two shells. In the first shell, start RViz and wait for everything to finish loading: ::
31+
32+
ros2 launch moveit2_tutorials move_group.launch.py
33+
34+
In the second shell, run the tutorial launch file: ::
35+
36+
ros2 launch moveit2_tutorials kinematics_cost_function_tutorial.launch.py
37+
38+
To progress through each demo step either press the **Next** button in the **RvizVisualToolsGui** panel at the bottom of the screen or select **Key Tool** in the **Tools** panel at the top of the screen and then press **0** on your keyboard while RViz is focused.
39+
40+
Expected Output
41+
---------------
42+
In RViz, we should be able to see the following:
43+
1. The robot moves its arm to the pose goal to its right. The L2 norm of the joint movement with and without the cost function specified is logged in the tutorial terminal.
44+
2. The robot moves its arm via a straight cartesian movement to the pose goal at its left.
45+
46+
The Entire Code
47+
---------------
48+
The entire code can be seen :codedir:`here in the MoveIt GitHub project<how_to_guides/kinematics_cost_function/src/kinematics_cost_function_tutorial.cpp>`. Next, we step through the code piece by piece to explain its functionality.
49+
50+
.. tutorial-formatter:: ./src/kinematics_cost_function_tutorial.cpp
51+
52+
The Launch File
53+
---------------
54+
The entire launch file is :codedir:`here<how_to_guides/kinematics_cost_function/launch/kinematics_cost_function_tutorial.launch.py>` on GitHub. All the code in this tutorial can be run from the **moveit2_tutorials** package that you have as part of your MoveIt setup.
Lines changed: 22 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,22 @@
1+
from launch import LaunchDescription
2+
from launch_ros.actions import Node
3+
from moveit_configs_utils import MoveItConfigsBuilder
4+
5+
6+
def generate_launch_description():
7+
moveit_config = MoveItConfigsBuilder("moveit_resources_panda").to_moveit_configs()
8+
9+
move_group_demo = Node(
10+
name="kinematics_cost_fn_tutorial",
11+
package="moveit2_tutorials",
12+
executable="kinematics_cost_function_tutorial",
13+
output="screen",
14+
parameters=[
15+
moveit_config.robot_description,
16+
moveit_config.robot_description_semantic,
17+
moveit_config.robot_description_kinematics,
18+
moveit_config.joint_limits,
19+
],
20+
)
21+
22+
return LaunchDescription([move_group_demo])
Lines changed: 256 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,256 @@
1+
/*********************************************************************
2+
* Software License Agreement (BSD License)
3+
*
4+
* Copyright (c) 2022, PickNik, Inc.
5+
* All rights reserved.
6+
*
7+
* Redistribution and use in source and binary forms, with or without
8+
* modification, are permitted provided that the following conditions
9+
* are met:
10+
*
11+
* * Redistributions of source code must retain the above copyright
12+
* notice, this list of conditions and the following disclaimer.
13+
* * Redistributions in binary form must reproduce the above
14+
* copyright notice, this list of conditions and the following
15+
* disclaimer in the documentation and/or other materials provided
16+
* with the distribution.
17+
* * Neither the name of SRI International nor the names of its
18+
* contributors may be used to endorse or promote products derived
19+
* from this software without specific prior written permission.
20+
*
21+
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22+
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23+
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24+
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25+
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26+
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27+
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28+
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29+
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30+
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31+
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32+
* POSSIBILITY OF SUCH DAMAGE.
33+
*********************************************************************/
34+
35+
/* Author: Wyatt Rees */
36+
#include <moveit/move_group_interface/move_group_interface.h>
37+
#include <moveit/planning_scene_interface/planning_scene_interface.h>
38+
#include <moveit/robot_state/cartesian_interpolator.h>
39+
#include <moveit/trajectory_processing/time_optimal_trajectory_generation.h>
40+
41+
#include <moveit_msgs/msg/display_robot_state.hpp>
42+
#include <moveit_msgs/msg/display_trajectory.hpp>
43+
#include <moveit_msgs/msg/attached_collision_object.hpp>
44+
#include <moveit_msgs/msg/collision_object.hpp>
45+
46+
#include <tf2_eigen/tf2_eigen.hpp>
47+
#include <moveit_visual_tools/moveit_visual_tools.h>
48+
49+
// All source files that use ROS logging should define a file-specific
50+
// static const rclcpp::Logger named LOGGER, located at the top of the file
51+
// and inside the namespace with the narrowest scope (if there is one)
52+
static const rclcpp::Logger LOGGER = rclcpp::get_logger("kinematics_cost_fn_demo");
53+
54+
int main(int argc, char** argv)
55+
{
56+
rclcpp::init(argc, argv);
57+
rclcpp::NodeOptions node_options;
58+
node_options.automatically_declare_parameters_from_overrides(true);
59+
auto node = rclcpp::Node::make_shared("kinematics_cost_fn_tutorial", node_options);
60+
61+
// We spin up a SingleThreadedExecutor for the current state monitor to get information
62+
// about the robot's state.
63+
rclcpp::executors::SingleThreadedExecutor executor;
64+
executor.add_node(node);
65+
std::thread([&executor]() { executor.spin(); }).detach();
66+
67+
// BEGIN_TUTORIAL
68+
//
69+
// Setup
70+
// ^^^^^
71+
//
72+
// MoveIt operates on sets of joints called "planning groups" and stores them in an object called
73+
// the ``JointModelGroup``. Throughout MoveIt, the terms "planning group" and "joint model group"
74+
// are used interchangeably.
75+
static const std::string PLANNING_GROUP = "panda_arm";
76+
77+
// The
78+
// :moveit_codedir:`MoveGroupInterface<moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h>`
79+
// class can be easily set up using just the name of the planning group you would like to control and plan for.
80+
moveit::planning_interface::MoveGroupInterface move_group(node, PLANNING_GROUP);
81+
82+
// Raw pointers are frequently used to refer to the planning group for improved performance.
83+
const moveit::core::JointModelGroup* joint_model_group =
84+
move_group.getCurrentState()->getJointModelGroup(PLANNING_GROUP);
85+
86+
// Visualization
87+
// ^^^^^^^^^^^^^
88+
namespace rvt = rviz_visual_tools;
89+
moveit_visual_tools::MoveItVisualTools visual_tools(node, "panda_link0", "move_group_tutorial",
90+
move_group.getRobotModel());
91+
92+
visual_tools.deleteAllMarkers();
93+
visual_tools.loadRemoteControl();
94+
95+
Eigen::Isometry3d text_pose = Eigen::Isometry3d::Identity();
96+
text_pose.translation().z() = 1.0;
97+
visual_tools.publishText(text_pose, "KinematicsCostFn_Demo", rvt::WHITE, rvt::XLARGE);
98+
99+
visual_tools.trigger();
100+
101+
// Start the demo
102+
// ^^^^^^^^^^^^^^^^^^^^^^^^^
103+
visual_tools.prompt("Press 'next' in the RvizVisualToolsGui window to start the demo");
104+
105+
// Computing IK solutions with cost functions
106+
// ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
107+
//
108+
// When computing IK solutions for goal poses, we can specify a cost function that will be used to
109+
// evaluate the "fitness" for a particular solution. At the time of writing this tutorial, this is
110+
// only supported by the bio_ik kinematics plugin.
111+
//
112+
//
113+
// To start, we'll create two pointers that references the current robot's state.
114+
// RobotState is the object that contains all the current position/velocity/acceleration data.
115+
// By making two copies, we can test the difference between IK calls that do/don't include cost functions
116+
moveit::core::RobotStatePtr current_state = move_group.getCurrentState(10);
117+
moveit::core::RobotStatePtr copy_state = move_group.getCurrentState(10);
118+
// We store the starting joint positions so we can evaluate performance later.
119+
std::vector<double> start_joint_positions;
120+
current_state->copyJointGroupPositions(joint_model_group, start_joint_positions);
121+
122+
// Set a target pose that we would like to solve IK for
123+
geometry_msgs::msg::Pose target_pose;
124+
target_pose.orientation.w = 1.0;
125+
target_pose.position.x = 0.28;
126+
target_pose.position.y = -0.2;
127+
target_pose.position.z = 0.5;
128+
129+
moveit::core::GroupStateValidityCallbackFn callback_fn;
130+
131+
// Cost functions usually require one to accept approximate IK solutions
132+
kinematics::KinematicsQueryOptions opts;
133+
opts.return_approximate_solution = true;
134+
135+
// Our cost function will optimize for minimal joint movement. Note that this is not the cost
136+
// function that we pass directly to the IK call, but a helper function that we can also use
137+
// to evaluate the solution.
138+
const auto compute_l2_norm = [](std::vector<double> solution, std::vector<double> start) {
139+
double sum = 0.0;
140+
for (size_t ji = 0; ji < solution.size(); ji++)
141+
{
142+
double d = solution[ji] - start[ji];
143+
sum += d * d;
144+
}
145+
return sum;
146+
};
147+
148+
// The weight of the cost function often needs tuning. A tradeoff exists between the accuracy of the
149+
// solution pose and the extent to which the IK solver obeys our cost function.
150+
const double weight = 0.0005;
151+
const auto cost_fn = [&weight, &compute_l2_norm](const geometry_msgs::msg::Pose& /*goal_pose*/,
152+
const moveit::core::RobotState& solution_state,
153+
moveit::core::JointModelGroup const* jmg,
154+
const std::vector<double>& seed_state) {
155+
std::vector<double> proposed_joint_positions;
156+
solution_state.copyJointGroupPositions(jmg, proposed_joint_positions);
157+
double cost = compute_l2_norm(proposed_joint_positions, seed_state);
158+
return weight * cost;
159+
};
160+
161+
// Now, we request an IK solution twice for the same pose. Once with a cost function, and once without.
162+
current_state->setFromIK(joint_model_group, target_pose, 0.0 /* timeout */, callback_fn, opts, cost_fn);
163+
copy_state->setFromIK(joint_model_group, target_pose, 0.0 /* timeout */, callback_fn, opts);
164+
165+
std::vector<double> solution;
166+
current_state->copyJointGroupPositions(joint_model_group, solution);
167+
168+
std::vector<double> solution_no_cost_fn;
169+
copy_state->copyJointGroupPositions(joint_model_group, solution_no_cost_fn);
170+
171+
// Now we can use our helper function from earlier to evaluate the effectiveness of the cost function.
172+
double l2_solution = compute_l2_norm(solution, start_joint_positions);
173+
RCLCPP_INFO_STREAM(LOGGER, "L2 norm of the solution WITH a cost function is " << l2_solution);
174+
l2_solution = compute_l2_norm(solution_no_cost_fn, start_joint_positions);
175+
RCLCPP_INFO_STREAM(LOGGER, "L2 norm of the solution WITHOUT a cost function is " << l2_solution);
176+
177+
// If we're happy with the solution, we can set it as a joint value target.
178+
move_group.setJointValueTarget(solution);
179+
180+
// We lower the allowed maximum velocity and acceleration to 5% of their maximum.
181+
// The default values are 10% (0.1).
182+
// Set your preferred defaults in the joint_limits.yaml file of your robot's moveit_config
183+
// or set explicit factors in your code if you need your robot to move faster.
184+
move_group.setMaxVelocityScalingFactor(0.05);
185+
move_group.setMaxAccelerationScalingFactor(0.05);
186+
187+
moveit::planning_interface::MoveGroupInterface::Plan my_plan;
188+
bool success = (move_group.plan(my_plan) == moveit::core::MoveItErrorCode::SUCCESS);
189+
RCLCPP_INFO(LOGGER, "Visualizing plan 1 (joint space goal with cost function) %s", success ? "" : "FAILED");
190+
191+
// Visualize the plan in RViz:
192+
visual_tools.deleteAllMarkers();
193+
visual_tools.publishAxisLabeled(target_pose, "goal_pose");
194+
visual_tools.publishText(text_pose, "Joint_Space_Goal", rvt::WHITE, rvt::XLARGE);
195+
visual_tools.publishTrajectoryLine(my_plan.trajectory, joint_model_group);
196+
visual_tools.trigger();
197+
198+
// Uncomment if you would like to execute the motion
199+
/*
200+
visual_tools.prompt("Press 'next' in the RvizVisualToolsGui window to execute the motion");
201+
move_group.execute(my_plan);
202+
*/
203+
204+
visual_tools.prompt("Press 'next' in the RvizVisualToolsGui window to continue.");
205+
206+
// We can also specify cost functions when computing robot trajectories that must follow a cartesian path.
207+
// First, let's change the target pose for the end of the path, so that if the previous motion plan was executed,
208+
// we still have somewhere to move.
209+
target_pose.position.y += 0.4;
210+
target_pose.position.z -= 0.1;
211+
target_pose.orientation.w = 0;
212+
target_pose.orientation.x = -1.0;
213+
Eigen::Isometry3d target;
214+
tf2::fromMsg(target_pose, target);
215+
216+
auto start_state = move_group.getCurrentState(10.0);
217+
std::vector<moveit::core::RobotStatePtr> traj;
218+
moveit::core::MaxEEFStep max_eef_step(0.01, 0.1);
219+
// Here, we're effectively disabling the jump threshold for joints. This is not recommended on real hardware.
220+
moveit::core::JumpThreshold jump_thresh(0.0);
221+
222+
// The trajectory, traj, passed to computeCartesianPath will contain several waypoints toward
223+
// the goal pose, target. For each of these waypoints, the IK solver is queried with the given cost function.
224+
const auto frac = moveit::core::CartesianInterpolator::computeCartesianPath(
225+
start_state.get(), joint_model_group, traj, joint_model_group->getLinkModel("panda_link8"), target, true,
226+
max_eef_step, jump_thresh, callback_fn, opts, cost_fn);
227+
228+
RCLCPP_INFO(LOGGER, "Computed %f percent of cartesian path.", frac.value * 100.0);
229+
230+
// Once we've computed the points in our Cartesian path, we need to add timestamps to each point for execution.
231+
robot_trajectory::RobotTrajectory rt(start_state->getRobotModel(), PLANNING_GROUP);
232+
for (const moveit::core::RobotStatePtr& traj_state : traj)
233+
rt.addSuffixWayPoint(traj_state, 0.0);
234+
trajectory_processing::TimeOptimalTrajectoryGeneration time_param;
235+
time_param.computeTimeStamps(rt, 1.0);
236+
237+
moveit_msgs::msg::RobotTrajectory rt_msg;
238+
rt.getRobotTrajectoryMsg(rt_msg);
239+
240+
visual_tools.deleteAllMarkers();
241+
visual_tools.publishTrajectoryLine(rt, joint_model_group);
242+
visual_tools.publishText(text_pose, "Cartesian_Path_Goal", rvt::WHITE, rvt::XLARGE);
243+
visual_tools.publishAxisLabeled(target_pose, "cartesian_goal_pose");
244+
visual_tools.trigger();
245+
246+
// Once we've computed the timestamps, we can pass the trajectory to move_group to execute it.
247+
move_group.execute(rt_msg);
248+
visual_tools.prompt("Press 'next' in the RvizVisualToolsGui window to end the demo.");
249+
250+
// END_TUTORIAL
251+
visual_tools.deleteAllMarkers();
252+
visual_tools.trigger();
253+
254+
rclcpp::shutdown();
255+
return 0;
256+
}

0 commit comments

Comments
 (0)