Skip to content

Commit

Permalink
Clang formatting
Browse files Browse the repository at this point in the history
  • Loading branch information
marip8 authored and Levi-Armstrong committed Oct 2, 2019
1 parent 8cb0e90 commit 9e7666d
Show file tree
Hide file tree
Showing 4 changed files with 8 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand Down Expand Up @@ -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*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,8 @@ class AxialApproachGenerator : public ProcessStepGenerator

tesseract_motion_planners::CartesianWaypoint::Ptr new_waypoint =
std::make_shared<tesseract_motion_planners::CartesianWaypoint>(
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);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,8 @@ class AxialDepartureGenerator : public ProcessStepGenerator

tesseract_motion_planners::CartesianWaypoint::Ptr new_waypoint =
std::make_shared<tesseract_motion_planners::CartesianWaypoint>(
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);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,8 @@ class PassthroughProcessGenerator : public ProcessStepGenerator
std::static_pointer_cast<tesseract_motion_planners::CartesianWaypoint>(waypoint);
tesseract_motion_planners::CartesianWaypoint::Ptr new_waypoint =
std::make_shared<tesseract_motion_planners::CartesianWaypoint>(
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);
Expand Down

0 comments on commit 9e7666d

Please sign in to comment.