Skip to content

Commit

Permalink
Cleanup PR feedback
Browse files Browse the repository at this point in the history
  • Loading branch information
marrts committed Mar 5, 2024
1 parent b85deb4 commit ea948d7
Show file tree
Hide file tree
Showing 3 changed files with 27 additions and 17 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -44,8 +44,8 @@ createCartesianWaypointTermInfo(int index,
const Eigen::Isometry3d& tcp_offset,
const Eigen::VectorXd& coeffs,
trajopt::TermType type,
const Eigen::VectorXd& lower_tolerance = Eigen::VectorXd::Zero(6),
const Eigen::VectorXd& upper_tolerance = Eigen::VectorXd::Zero(6));
const Eigen::VectorXd& lower_tolerance = Eigen::VectorXd(),
const Eigen::VectorXd& upper_tolerance = Eigen::VectorXd());

trajopt::TermInfo::Ptr
createDynamicCartesianWaypointTermInfo(int index,
Expand All @@ -55,8 +55,8 @@ createDynamicCartesianWaypointTermInfo(int index,
const Eigen::Isometry3d& tcp_offset,
const Eigen::VectorXd& coeffs,
trajopt::TermType type,
const Eigen::VectorXd& lower_tolerance = Eigen::VectorXd::Zero(6),
const Eigen::VectorXd& upper_tolerance = Eigen::VectorXd::Zero(6));
const Eigen::VectorXd& lower_tolerance = Eigen::VectorXd(),
const Eigen::VectorXd& upper_tolerance = Eigen::VectorXd());

trajopt::TermInfo::Ptr createNearJointStateTermInfo(const Eigen::VectorXd& target,
const std::vector<std::string>& joint_names,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,40 +27,44 @@
#define TESSERACT_MOTION_PLANNERS_TRAJOPT_CONFIG_TRAJOPT_WAYPOINT_CONFIG_H

#include <tesseract_common/macros.h>
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
#include <trajopt/problem_description.hpp>
#include <tinyxml2.h>
#include <boost/algorithm/string.hpp>
TESSERACT_COMMON_IGNORE_WARNINGS_POP

#include <tesseract_common/utils.h>

namespace tinyxml2
{
class XMLElement;
class XMLDocument;
}

namespace tesseract_planning
{
/**
* @brief Config settings for cartesian waypoints
*/
struct CartesianWaypointConfig
{
// LCOV_EXCL_START
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
// LCOV_EXCL_STOP

CartesianWaypointConfig() = default;
CartesianWaypointConfig(const tinyxml2::XMLElement& xml_element);

/** @brief If true, a cost/constraint term will be added to the problem. Default: true*/
bool enabled = true;
bool enabled{ true };

/** @brief If true, will override existing waypoint tolerance with described tolerance here. Default: false
* This is useful if you want to have a smaller tolerance for the cost than the constraint.*/
bool use_tolerance_override = false;
bool use_tolerance_override{ false };

/** @brief Distance below waypoint that is allowed. Should be size = 6. First 3 elements are dx, dy, dz. The last 3
* elements are angle axis error allowed (Eigen::AngleAxisd.axis() * Eigen::AngleAxisd.angle()) */
Eigen::VectorXd lower_tolerance;
Eigen::Matrix<double, 6, 1> lower_tolerance;
/** @brief Distance above waypoint that is allowed. Should be size = 6. First 3 elements are dx, dy, dz. The last 3
* elements are angle axis error allowed (Eigen::AngleAxisd.axis() * Eigen::AngleAxisd.angle())*/
Eigen::VectorXd upper_tolerance;
Eigen::Matrix<double, 6, 1> upper_tolerance;

/** @brief coefficients corresponsing to dx, dy, dz, rx, ry, rz*/
Eigen::VectorXd coeff{ Eigen::VectorXd::Constant(1, 1, 5) };
Eigen::Matrix<double, 6, 1> coeff{ Eigen::VectorXd::Constant(6, 5) };

tinyxml2::XMLElement* toXML(tinyxml2::XMLDocument& doc) const;
};
Expand All @@ -70,15 +74,19 @@ struct CartesianWaypointConfig
*/
struct JointWaypointConfig
{
// LCOV_EXCL_START
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
// LCOV_EXCL_STOP

JointWaypointConfig() = default;
JointWaypointConfig(const tinyxml2::XMLElement& xml_element);

/** @brief If true, a cost/constraint term will be added to the problem. Default: true*/
bool enabled = true;
bool enabled{ true };

/** @brief If true, will override existing waypoint tolerance with described tolerance here. Default: false
* This is useful if you want to have a smaller tolerance for the cost than the constraint.*/
bool use_tolerance_override = false;
bool use_tolerance_override{ false };

/** @brief Distance below waypoint that is allowed. Should be size of joints in a joint state*/
Eigen::VectorXd lower_tolerance;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,9 @@
#include <tesseract_common/macros.h>
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
#include <stdexcept>
#include <tinyxml2.h>
#include <iostream>
#include <boost/algorithm/string.hpp>
TESSERACT_COMMON_IGNORE_WARNINGS_POP

#include <tesseract_motion_planners/trajopt/trajopt_waypoint_config.h>
Expand Down

0 comments on commit ea948d7

Please sign in to comment.