diff --git a/tesseract/tesseract_planning/tesseract_motion_planners/include/tesseract_motion_planners/core/waypoint.h b/tesseract/tesseract_planning/tesseract_motion_planners/include/tesseract_motion_planners/core/waypoint.h index 951a0f6aecb..1d9a8dc1827 100644 --- a/tesseract/tesseract_planning/tesseract_motion_planners/include/tesseract_motion_planners/core/waypoint.h +++ b/tesseract/tesseract_planning/tesseract_motion_planners/include/tesseract_motion_planners/core/waypoint.h @@ -179,8 +179,7 @@ class CartesianWaypoint : public Waypoint } CartesianWaypoint(Eigen::Vector3d position, Eigen::Quaterniond orientation, std::string link = "") - : Waypoint(WaypointType::CARTESIAN_WAYPOINT) - , parent_link_(std::move(link)) + : Waypoint(WaypointType::CARTESIAN_WAYPOINT), parent_link_(std::move(link)) { cartesian_position_.translation() = position; cartesian_position_.linear() = orientation.toRotationMatrix(); @@ -210,7 +209,7 @@ class CartesianWaypoint : public Waypoint protected: Eigen::Isometry3d cartesian_position_; /** @brief Pose of this waypoint */ - std::string parent_link_; /** @brief The link to which this position is defined */ + std::string parent_link_; /** @brief The link to which this position is defined */ }; /** @brief Defines a joint toleranced position waypoint for use with Tesseract Planners*/ diff --git a/tesseract/tesseract_planning/tesseract_process_planners/include/tesseract_process_planners/generators/axial_approach_generator.h b/tesseract/tesseract_planning/tesseract_process_planners/include/tesseract_process_planners/generators/axial_approach_generator.h index f38a612cb30..d099cca77a5 100644 --- a/tesseract/tesseract_planning/tesseract_process_planners/include/tesseract_process_planners/generators/axial_approach_generator.h +++ b/tesseract/tesseract_planning/tesseract_process_planners/include/tesseract_process_planners/generators/axial_approach_generator.h @@ -33,7 +33,8 @@ class AxialApproachGenerator : public ProcessStepGenerator tesseract_motion_planners::CartesianWaypoint::Ptr new_waypoint = std::make_shared( - config.world_offset_direction * cur_waypoint->getTransform() * config.local_offset_direction * scaled, cur_waypoint->getParentLinkName()); + config.world_offset_direction * cur_waypoint->getTransform() * config.local_offset_direction * scaled, + cur_waypoint->getParentLinkName()); new_waypoint->setCoefficients(cur_waypoint->getCoefficients()); new_waypoint->setIsCritical(cur_waypoint->isCritical()); approach.push_back(new_waypoint); diff --git a/tesseract/tesseract_planning/tesseract_process_planners/include/tesseract_process_planners/generators/axial_departure_generator.h b/tesseract/tesseract_planning/tesseract_process_planners/include/tesseract_process_planners/generators/axial_departure_generator.h index b77b8547c27..1cf058e13f5 100644 --- a/tesseract/tesseract_planning/tesseract_process_planners/include/tesseract_process_planners/generators/axial_departure_generator.h +++ b/tesseract/tesseract_planning/tesseract_process_planners/include/tesseract_process_planners/generators/axial_departure_generator.h @@ -33,7 +33,8 @@ class AxialDepartureGenerator : public ProcessStepGenerator tesseract_motion_planners::CartesianWaypoint::Ptr new_waypoint = std::make_shared( - config.world_offset_direction * cur_waypoint->getTransform() * config.local_offset_direction * scaled, cur_waypoint->getParentLinkName()); + config.world_offset_direction * cur_waypoint->getTransform() * config.local_offset_direction * scaled, + cur_waypoint->getParentLinkName()); new_waypoint->setCoefficients(cur_waypoint->getCoefficients()); new_waypoint->setIsCritical(cur_waypoint->isCritical()); departure.push_back(new_waypoint); diff --git a/tesseract/tesseract_planning/tesseract_process_planners/include/tesseract_process_planners/generators/passthrough_process_generator.h b/tesseract/tesseract_planning/tesseract_process_planners/include/tesseract_process_planners/generators/passthrough_process_generator.h index bd2a24bb623..690b9456757 100644 --- a/tesseract/tesseract_planning/tesseract_process_planners/include/tesseract_process_planners/generators/passthrough_process_generator.h +++ b/tesseract/tesseract_planning/tesseract_process_planners/include/tesseract_process_planners/generators/passthrough_process_generator.h @@ -24,7 +24,8 @@ class PassthroughProcessGenerator : public ProcessStepGenerator std::static_pointer_cast(waypoint); tesseract_motion_planners::CartesianWaypoint::Ptr new_waypoint = std::make_shared( - config.world_offset_direction * cur_waypoint->getTransform() * config.local_offset_direction, cur_waypoint->getParentLinkName()); + config.world_offset_direction * cur_waypoint->getTransform() * config.local_offset_direction, + cur_waypoint->getParentLinkName()); new_waypoint->setCoefficients(cur_waypoint->getCoefficients()); new_waypoint->setIsCritical(cur_waypoint->isCritical()); new_waypoints.push_back(new_waypoint);