Skip to content

Commit

Permalink
Fix format
Browse files Browse the repository at this point in the history
Signed-off-by: Ryan Friedman <[email protected]>
  • Loading branch information
Ryanf55 committed Nov 29, 2024
1 parent 0a770a1 commit fbfdb8f
Showing 1 changed file with 15 additions and 10 deletions.
25 changes: 15 additions & 10 deletions terrain_planner_benchmark/src/terrain_planner_benchmark_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,16 +38,16 @@
* @author Jaeyoung Lim <[email protected]>
*/

#include <geometry_msgs/msg/point.hpp>
#include <rclcpp/rclcpp.hpp>
#include <terrain_navigation/terrain_map.h>
#include <tf2/LinearMath/Quaternion.h>

#include <geometry_msgs/msg/point.hpp>
#include <grid_map_ros/GridMapRosConverter.hpp>
#include <rclcpp/rclcpp.hpp>
#include <tf2_eigen/tf2_eigen.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#include <visualization_msgs/msg/marker_array.hpp>

#include <grid_map_ros/GridMapRosConverter.hpp>

#include "terrain_planner/common.h"
#include "terrain_planner/terrain_ompl_rrt.h"
#include "terrain_planner/visualization.h"
Expand All @@ -57,14 +57,19 @@ int main(int argc, char** argv) {
rclcpp::init(argc, argv);
auto node = rclcpp::Node::make_shared("ompl_rrt_planner");

// Initialize ROS related publishers for visualization
auto start_pos_pub = node->create_publisher<visualization_msgs::msg::Marker>("start_position", rclcpp::QoS(1).transient_local());
auto goal_pos_pub = node->create_publisher<visualization_msgs::msg::Marker>("goal_position", rclcpp::QoS(1).transient_local());
// Initialize ROS related publishers for visualization
auto start_pos_pub =
node->create_publisher<visualization_msgs::msg::Marker>("start_position", rclcpp::QoS(1).transient_local());
auto goal_pos_pub =
node->create_publisher<visualization_msgs::msg::Marker>("goal_position", rclcpp::QoS(1).transient_local());
auto path_pub = node->create_publisher<nav_msgs::msg::Path>("path", rclcpp::QoS(1).transient_local());
auto interpolate_path_pub = node->create_publisher<nav_msgs::msg::Path>("interpolated_path", rclcpp::QoS(1).transient_local());
auto path_segment_pub = node->create_publisher<visualization_msgs::msg::MarkerArray>("path_segments", rclcpp::QoS(1).transient_local());
auto interpolate_path_pub =
node->create_publisher<nav_msgs::msg::Path>("interpolated_path", rclcpp::QoS(1).transient_local());
auto path_segment_pub =
node->create_publisher<visualization_msgs::msg::MarkerArray>("path_segments", rclcpp::QoS(1).transient_local());
auto grid_map_pub = node->create_publisher<grid_map_msgs::msg::GridMap>("grid_map", rclcpp::QoS(1).transient_local());
auto trajectory_pub = node->create_publisher<visualization_msgs::msg::MarkerArray>("tree", rclcpp::QoS(1).transient_local());
auto trajectory_pub =
node->create_publisher<visualization_msgs::msg::MarkerArray>("tree", rclcpp::QoS(1).transient_local());

auto const map_path = node->declare_parameter("map_path", "");
auto const location = node->declare_parameter("location", "");
Expand Down

0 comments on commit fbfdb8f

Please sign in to comment.