Skip to content

Commit d2fa313

Browse files
committed
Add toleranced waypoints to TrajOpt Solver
1 parent d2b11de commit d2fa313

File tree

12 files changed

+556
-119
lines changed

12 files changed

+556
-119
lines changed

tesseract_examples/src/basic_cartesian_example.cpp

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -231,8 +231,12 @@ bool BasicCartesianExample::run()
231231
profiles->addProfile<TrajOptCompositeProfile>(TRAJOPT_DEFAULT_NAMESPACE, "cartesian_program", composite_profile);
232232

233233
auto plan_profile = std::make_shared<TrajOptDefaultPlanProfile>();
234-
plan_profile->cartesian_coeff = Eigen::VectorXd::Ones(6);
235-
plan_profile->joint_coeff = Eigen::VectorXd::Ones(7);
234+
plan_profile->cartesian_cost_config.enabled = false;
235+
plan_profile->cartesian_constraint_config.enabled = true;
236+
plan_profile->cartesian_constraint_config.coeff = Eigen::VectorXd::Ones(6);
237+
plan_profile->joint_cost_config.enabled = false;
238+
plan_profile->joint_constraint_config.enabled = true;
239+
plan_profile->joint_constraint_config.coeff = Eigen::VectorXd::Ones(7);
236240
profiles->addProfile<TrajOptPlanProfile>(TRAJOPT_DEFAULT_NAMESPACE, "RASTER", plan_profile);
237241
profiles->addProfile<TrajOptPlanProfile>(TRAJOPT_DEFAULT_NAMESPACE, "freespace_profile", plan_profile);
238242
}

tesseract_examples/src/glass_upright_example.cpp

Lines changed: 6 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -221,10 +221,12 @@ bool GlassUprightExample::run()
221221
profiles->addProfile<TrajOptCompositeProfile>(TRAJOPT_DEFAULT_NAMESPACE, "UPRIGHT", composite_profile);
222222

223223
auto plan_profile = std::make_shared<TrajOptDefaultPlanProfile>();
224-
plan_profile->cartesian_coeff = Eigen::VectorXd::Constant(6, 1, 5);
225-
plan_profile->cartesian_coeff(0) = 0;
226-
plan_profile->cartesian_coeff(1) = 0;
227-
plan_profile->cartesian_coeff(2) = 0;
224+
plan_profile->cartesian_cost_config.enabled = false;
225+
plan_profile->cartesian_constraint_config.enabled = true;
226+
plan_profile->cartesian_constraint_config.coeff = Eigen::VectorXd::Constant(6, 1, 5);
227+
plan_profile->cartesian_constraint_config.coeff(0) = 0;
228+
plan_profile->cartesian_constraint_config.coeff(1) = 0;
229+
plan_profile->cartesian_constraint_config.coeff(2) = 0;
228230

229231
// Add profile to Dictionary
230232
profiles->addProfile<TrajOptPlanProfile>(TRAJOPT_DEFAULT_NAMESPACE, "UPRIGHT", plan_profile);

tesseract_examples/src/pick_and_place_example.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -193,7 +193,9 @@ bool PickAndPlaceExample::run()
193193

194194
// Create TrajOpt Profile
195195
auto trajopt_plan_profile = std::make_shared<TrajOptDefaultPlanProfile>();
196-
trajopt_plan_profile->cartesian_coeff = Eigen::VectorXd::Constant(6, 1, 10);
196+
trajopt_plan_profile->cartesian_cost_config.enabled = false;
197+
trajopt_plan_profile->cartesian_constraint_config.enabled = true;
198+
trajopt_plan_profile->cartesian_constraint_config.coeff = Eigen::VectorXd::Constant(6, 1, 10);
197199

198200
auto trajopt_composite_profile = std::make_shared<TrajOptDefaultCompositeProfile>();
199201
trajopt_composite_profile->longest_valid_segment_length = 0.05;

tesseract_examples/src/puzzle_piece_auxillary_axes_example.cpp

Lines changed: 6 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -197,10 +197,12 @@ bool PuzzlePieceAuxillaryAxesExample::run()
197197

198198
// Create TrajOpt Profile
199199
auto trajopt_plan_profile = std::make_shared<tesseract_planning::TrajOptDefaultPlanProfile>();
200-
trajopt_plan_profile->cartesian_coeff = Eigen::VectorXd::Constant(6, 1, 5);
201-
trajopt_plan_profile->cartesian_coeff(3) = 2;
202-
trajopt_plan_profile->cartesian_coeff(4) = 2;
203-
trajopt_plan_profile->cartesian_coeff(5) = 0;
200+
trajopt_plan_profile->cartesian_cost_config.enabled = false;
201+
trajopt_plan_profile->cartesian_constraint_config.enabled = true;
202+
trajopt_plan_profile->cartesian_constraint_config.coeff = Eigen::VectorXd::Constant(6, 1, 5);
203+
trajopt_plan_profile->cartesian_constraint_config.coeff(3) = 2;
204+
trajopt_plan_profile->cartesian_constraint_config.coeff(4) = 2;
205+
trajopt_plan_profile->cartesian_constraint_config.coeff(5) = 0;
204206

205207
auto trajopt_composite_profile = std::make_shared<TrajOptDefaultCompositeProfile>();
206208
trajopt_composite_profile->collision_constraint_config.enabled = false;

tesseract_examples/src/puzzle_piece_example.cpp

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -193,8 +193,10 @@ bool PuzzlePieceExample::run()
193193

194194
// Create TrajOpt Profile
195195
auto trajopt_plan_profile = std::make_shared<TrajOptDefaultPlanProfile>();
196-
trajopt_plan_profile->cartesian_coeff = Eigen::VectorXd::Constant(6, 1, 10);
197-
trajopt_plan_profile->cartesian_coeff(5) = 0;
196+
trajopt_plan_profile->cartesian_cost_config.enabled = false;
197+
trajopt_plan_profile->cartesian_constraint_config.enabled = true;
198+
trajopt_plan_profile->cartesian_constraint_config.coeff = Eigen::VectorXd::Constant(6, 1, 10);
199+
trajopt_plan_profile->cartesian_constraint_config.coeff(5) = 0;
198200

199201
auto trajopt_composite_profile = std::make_shared<TrajOptDefaultCompositeProfile>();
200202
trajopt_composite_profile->collision_constraint_config.enabled = false;

tesseract_motion_planners/trajopt/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,7 @@ find_package(trajopt_sco REQUIRED)
55
add_library(
66
${PROJECT_NAME}_trajopt
77
src/trajopt_collision_config.cpp
8+
src/trajopt_waypoint_config.cpp
89
src/trajopt_motion_planner.cpp
910
src/trajopt_utils.cpp
1011
src/profile/trajopt_default_plan_profile.cpp

tesseract_motion_planners/trajopt/include/tesseract_motion_planners/trajopt/profile/trajopt_default_plan_profile.h

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,7 @@ TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
3333
#include <Eigen/Geometry>
3434
TESSERACT_COMMON_IGNORE_WARNINGS_POP
3535

36+
#include <tesseract_motion_planners/trajopt/trajopt_waypoint_config.h>
3637
#include <tesseract_motion_planners/trajopt/profile/trajopt_profile.h>
3738

3839
namespace tesseract_planning
@@ -51,9 +52,10 @@ class TrajOptDefaultPlanProfile : public TrajOptPlanProfile
5152
TrajOptDefaultPlanProfile(TrajOptDefaultPlanProfile&&) = default;
5253
TrajOptDefaultPlanProfile& operator=(TrajOptDefaultPlanProfile&&) = default;
5354

54-
Eigen::VectorXd cartesian_coeff{ Eigen::VectorXd::Constant(1, 1, 5) };
55-
Eigen::VectorXd joint_coeff{ Eigen::VectorXd::Constant(1, 1, 5) };
56-
trajopt::TermType term_type{ trajopt::TermType::TT_CNT };
55+
CartesianWaypointConfig cartesian_cost_config;
56+
CartesianWaypointConfig cartesian_constraint_config;
57+
JointWaypointConfig joint_cost_config;
58+
JointWaypointConfig joint_constraint_config;
5759

5860
/** @brief Error function that is set as a constraint for each timestep.
5961
*

tesseract_motion_planners/trajopt/include/tesseract_motion_planners/trajopt/trajopt_utils.h

Lines changed: 14 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -42,15 +42,20 @@ trajopt::TermInfo::Ptr createCartesianWaypointTermInfo(int index,
4242
const std::string& tcp_frame,
4343
const Eigen::Isometry3d& tcp_offset,
4444
const Eigen::VectorXd& coeffs,
45-
trajopt::TermType type);
46-
47-
trajopt::TermInfo::Ptr createDynamicCartesianWaypointTermInfo(int index,
48-
const std::string& working_frame,
49-
const Eigen::Isometry3d& c_wp,
50-
const std::string& tcp_frame,
51-
const Eigen::Isometry3d& tcp_offset,
52-
const Eigen::VectorXd& coeffs,
53-
trajopt::TermType type);
45+
trajopt::TermType type,
46+
Eigen::VectorXd lower_tolerance = Eigen::VectorXd::Zero(6),
47+
Eigen::VectorXd upper_tolerance = Eigen::VectorXd::Zero(6));
48+
49+
trajopt::TermInfo::Ptr
50+
createDynamicCartesianWaypointTermInfo(int index,
51+
const std::string& working_frame,
52+
const Eigen::Isometry3d& c_wp,
53+
const std::string& tcp_frame,
54+
const Eigen::Isometry3d& tcp_offset,
55+
const Eigen::VectorXd& coeffs,
56+
trajopt::TermType type,
57+
Eigen::VectorXd lower_tolerance = Eigen::VectorXd::Zero(6),
58+
Eigen::VectorXd upper_tolerance = Eigen::VectorXd::Zero(6));
5459

5560
trajopt::TermInfo::Ptr createNearJointStateTermInfo(const Eigen::VectorXd& target,
5661
const std::vector<std::string>& joint_names,
Lines changed: 95 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,95 @@
1+
/**
2+
* @file trajopt_waypoint_config.h
3+
* @brief TrajOpt waypoint configuration settings
4+
*
5+
* @author Tyler Marr
6+
* @date November 2, 2023
7+
* @version TODO
8+
* @bug No known bugs
9+
*
10+
* @copyright Copyright (c) 2023, Southwest Research Institute
11+
*
12+
* @par License
13+
* Software License Agreement (Apache License)
14+
* @par
15+
* Licensed under the Apache License, Version 2.0 (the "License");
16+
* you may not use this file except in compliance with the License.
17+
* You may obtain a copy of the License at
18+
* http://www.apache.org/licenses/LICENSE-2.0
19+
* @par
20+
* Unless required by applicable law or agreed to in writing, software
21+
* distributed under the License is distributed on an "AS IS" BASIS,
22+
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
23+
* See the License for the specific language governing permissions and
24+
* limitations under the License.
25+
*/
26+
#ifndef TESSERACT_MOTION_PLANNERS_TRAJOPT_CONFIG_TRAJOPT_WAYPOINT_CONFIG_H
27+
#define TESSERACT_MOTION_PLANNERS_TRAJOPT_CONFIG_TRAJOPT_WAYPOINT_CONFIG_H
28+
29+
#include <tesseract_common/macros.h>
30+
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
31+
#include <trajopt/problem_description.hpp>
32+
#include <tinyxml2.h>
33+
#include <boost/algorithm/string.hpp>
34+
TESSERACT_COMMON_IGNORE_WARNINGS_POP
35+
36+
#include <tesseract_common/utils.h>
37+
38+
namespace tesseract_planning
39+
{
40+
/**
41+
* @brief Config settings for cartesian waypoints
42+
*/
43+
struct CartesianWaypointConfig
44+
{
45+
CartesianWaypointConfig() = default;
46+
CartesianWaypointConfig(const tinyxml2::XMLElement& xml_element);
47+
48+
/** @brief If true, a cost/constraint term will be added to the problem. Default: true*/
49+
bool enabled = true;
50+
51+
/** @brief If true, will override existing waypoint tolerance with described tolerance here. Default: false
52+
* This is useful if you want to have a smaller tolerance for the cost than the constraint.*/
53+
bool use_tolerance_override = false;
54+
55+
/** @brief Distance below waypoint that is allowed. Should be size = 6. First 3 elements are dx, dy, dz. The last 3
56+
* elements are angle axis error allowed (Eigen::AngleAxisd.axis() * Eigen::AngleAxisd.angle()) */
57+
Eigen::VectorXd lower_tolerance;
58+
/** @brief Distance above waypoint that is allowed. Should be size = 6. First 3 elements are dx, dy, dz. The last 3
59+
* elements are angle axis error allowed (Eigen::AngleAxisd.axis() * Eigen::AngleAxisd.angle())*/
60+
Eigen::VectorXd upper_tolerance;
61+
62+
/** @brief coefficients corresponsing to dx, dy, dz, rx, ry, rz*/
63+
Eigen::VectorXd coeff{ Eigen::VectorXd::Constant(1, 1, 5) };
64+
65+
tinyxml2::XMLElement* toXML(tinyxml2::XMLDocument& doc) const;
66+
};
67+
68+
/**
69+
* @brief Config settings for joint waypoints.
70+
*/
71+
struct JointWaypointConfig
72+
{
73+
JointWaypointConfig() = default;
74+
JointWaypointConfig(const tinyxml2::XMLElement& xml_element);
75+
76+
/** @brief If true, a cost/constraint term will be added to the problem. Default: true*/
77+
bool enabled = true;
78+
79+
/** @brief If true, will override existing waypoint tolerance with described tolerance here. Default: false
80+
* This is useful if you want to have a smaller tolerance for the cost than the constraint.*/
81+
bool use_tolerance_override = false;
82+
83+
/** @brief Distance below waypoint that is allowed. Should be size of joints in a joint state*/
84+
Eigen::VectorXd lower_tolerance;
85+
/** @brief Distance above waypoint that is allowed. Should be size of joints in a joint state*/
86+
Eigen::VectorXd upper_tolerance;
87+
88+
/** @brief coefficients corresponsing to joint values*/
89+
Eigen::VectorXd coeff{ Eigen::VectorXd::Constant(1, 1, 5) };
90+
91+
tinyxml2::XMLElement* toXML(tinyxml2::XMLDocument& doc) const;
92+
};
93+
} // namespace tesseract_planning
94+
95+
#endif // TESSERACT_MOTION_PLANNERS_TRAJOPT_CONFIG_TRAJOPT_WAYPOINT_CONFIG_H

0 commit comments

Comments
 (0)