Skip to content

Commit

Permalink
fix(behavior_path_planner): fix build error in Humble (#468)
Browse files Browse the repository at this point in the history
* fix(behavior_path_planner): fix build error in Humble

* ci(pre-commit): autofix

---------

Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
  • Loading branch information
h-ohta and pre-commit-ci[bot] committed May 15, 2023
1 parent 8553fd3 commit 75cc7bf
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 32 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@
#include <geometry_msgs/msg/point.hpp>
#include <geometry_msgs/msg/pose.hpp>
#include <geometry_msgs/msg/pose_array.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>

#include <boost/geometry/geometries/box.hpp>
#include <boost/geometry/geometries/point_xy.hpp>
Expand All @@ -45,7 +46,6 @@
#include <lanelet2_routing/RoutingGraph.h>
#include <lanelet2_routing/RoutingGraphContainer.h>
#include <tf2/utils.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>

#include <limits>
#include <memory>
Expand Down Expand Up @@ -79,36 +79,6 @@ inline void fromMsg(const geometry_msgs::msg::PoseStamped & msg, tf2::Stamped<tf
fromMsg(msg.pose, tmp);
out.setData(tmp);
}

// Remove after this commit is released
// https://github.com/ros2/geometry2/commit/e9da371d81e388a589540357c050e262442f1b4a
inline geometry_msgs::msg::Point & toMsg(const tf2::Vector3 & in, geometry_msgs::msg::Point & out)
{
out.x = in.getX();
out.y = in.getY();
out.z = in.getZ();
return out;
}

// Remove after this commit is released
// https://github.com/ros2/geometry2/commit/e9da371d81e388a589540357c050e262442f1b4a
inline void fromMsg(const geometry_msgs::msg::Point & in, tf2::Vector3 & out)
{
out = tf2::Vector3(in.x, in.y, in.z);
}

template <>
inline void doTransform(
const geometry_msgs::msg::Point & t_in, geometry_msgs::msg::Point & t_out,
const geometry_msgs::msg::TransformStamped & transform)
{
tf2::Transform t;
fromMsg(transform.transform, t);
tf2::Vector3 v_in;
fromMsg(t_in, v_in);
tf2::Vector3 v_out = t * v_in;
toMsg(v_out, t_out);
}
} // namespace tf2

namespace behavior_path_planner
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2449,7 +2449,7 @@ void AvoidanceModule::updateRegisteredObject(const ObjectDataArray & now_objects
};

// -- check now_objects, add it if it has new object id --
for (const auto now_obj : now_objects) {
for (const auto & now_obj : now_objects) {
if (!isAlreadyRegistered(now_obj.object.object_id)) {
registered_objects_.push_back(now_obj);
}
Expand Down

0 comments on commit 75cc7bf

Please sign in to comment.