Skip to content

Commit

Permalink
Fix ci-testing build issues (#1998)
Browse files Browse the repository at this point in the history
  • Loading branch information
henningkayser committed Mar 10, 2023
2 parents b68db4e + 31e07d3 commit 0e1c973
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 10 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@

namespace planning_request_adapter
{
rclcpp::Logger LOGGER = rclcpp::get_logger("moveit").get_child("planning_request_adapter");
static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.planning_request_adapter");

namespace
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -315,19 +315,19 @@ class RobotTrajectory

class Iterator
{
std::deque<moveit::core::RobotStatePtr>::iterator waypoint_iterator;
std::deque<double>::iterator duration_iterator;
std::deque<moveit::core::RobotStatePtr>::iterator waypoint_iterator_;
std::deque<double>::iterator duration_iterator_;

public:
explicit Iterator(const std::deque<moveit::core::RobotStatePtr>::iterator& _waypoint_iterator,
const std::deque<double>::iterator& _duration_iterator)
: waypoint_iterator(_waypoint_iterator), duration_iterator(_duration_iterator)
explicit Iterator(const std::deque<moveit::core::RobotStatePtr>::iterator& waypoint_iterator,
const std::deque<double>::iterator& duration_iterator)
: waypoint_iterator_(waypoint_iterator), duration_iterator_(duration_iterator)
{
}
Iterator& operator++()
{
waypoint_iterator++;
duration_iterator++;
waypoint_iterator_++;
duration_iterator_++;
return *this;
}
Iterator operator++(int)
Expand All @@ -338,15 +338,15 @@ class RobotTrajectory
}
bool operator==(const Iterator& other) const
{
return ((waypoint_iterator == other.waypoint_iterator) && (duration_iterator == other.duration_iterator));
return ((waypoint_iterator_ == other.waypoint_iterator_) && (duration_iterator_ == other.duration_iterator_));
}
bool operator!=(const Iterator& other) const
{
return !(*this == other);
}
std::pair<moveit::core::RobotStatePtr, double> operator*() const
{
return std::pair{ *waypoint_iterator, *duration_iterator };
return std::pair{ *waypoint_iterator_, *duration_iterator_ };
}

// iterator traits
Expand Down

0 comments on commit 0e1c973

Please sign in to comment.