Skip to content

Commit

Permalink
Fixed failing serialization test
Browse files Browse the repository at this point in the history
  • Loading branch information
marrts committed Mar 7, 2024
1 parent 2670523 commit 3f9ae08
Show file tree
Hide file tree
Showing 3 changed files with 7 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -59,10 +59,10 @@ struct CartesianWaypointConfig

/** @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::Matrix<double, 6, 1> lower_tolerance;
Eigen::Matrix<double, 6, 1> lower_tolerance{ Eigen::VectorXd::Zero(6) };
/** @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::Matrix<double, 6, 1> upper_tolerance;
Eigen::Matrix<double, 6, 1> upper_tolerance{ Eigen::VectorXd::Zero(6) };

/** @brief coefficients corresponsing to dx, dy, dz, rx, ry, rz*/
Eigen::Matrix<double, 6, 1> coeff{ Eigen::VectorXd::Constant(6, 5) };
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -63,15 +63,15 @@ TrajOptDefaultPlanProfile::TrajOptDefaultPlanProfile(const tinyxml2::XMLElement&

if (joint_cost_element != nullptr)
{
const tinyxml2::XMLElement* cartesian_waypoint_config = joint_cost_element->FirstChildElement("CartesianWaypointCon"
"fig");
const tinyxml2::XMLElement* cartesian_waypoint_config = joint_cost_element->FirstChildElement("JointWaypointConfi"
"g");
joint_cost_config = JointWaypointConfig(*cartesian_waypoint_config);
}

if (joint_constraint_element != nullptr)
{
const tinyxml2::XMLElement* cartesian_waypoint_config = joint_constraint_element->FirstChildElement("CartesianWaypo"
"intConfig");
const tinyxml2::XMLElement* cartesian_waypoint_config = joint_constraint_element->FirstChildElement("JointWaypointC"
"onfig");
joint_constraint_config = JointWaypointConfig(*cartesian_waypoint_config);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -235,7 +235,7 @@ tinyxml2::XMLElement* JointWaypointConfig::toXML(tinyxml2::XMLDocument& doc) con
{
Eigen::IOFormat eigen_format(Eigen::StreamPrecision, Eigen::DontAlignCols, " ", " ");

tinyxml2::XMLElement* xml_cartesian_waypoint_config = doc.NewElement("CartesianWaypointConfig");
tinyxml2::XMLElement* xml_cartesian_waypoint_config = doc.NewElement("JointWaypointConfig");

tinyxml2::XMLElement* xml_enabled = doc.NewElement("Enabled");
xml_enabled->SetText(enabled);
Expand Down

0 comments on commit 3f9ae08

Please sign in to comment.