Skip to content

Commit

Permalink
reformat clang-format with 100 column width
Browse files Browse the repository at this point in the history
  • Loading branch information
jlblancoc committed Sep 13, 2024
1 parent d1e392f commit 3d7521c
Show file tree
Hide file tree
Showing 23 changed files with 639 additions and 1,164 deletions.
2 changes: 1 addition & 1 deletion .clang-format
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ AlignTrailingComments: false # Should be off, causes many dummy problems!!
BreakBeforeBraces: Allman
#BreakBeforeTernaryOperators: true
#BreakConstructorInitializersBeforeComma: false
ColumnLimit: 80
ColumnLimit: 100
#CommentPragmas: ''
#ConstructorInitializerAllOnOneLineOrOnePerLine: true
#ConstructorInitializerIndentWidth: 4
Expand Down
3 changes: 3 additions & 0 deletions clang-formatter.sh
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
#!/bin/bash

find mrpt_*/ -iname *.h -o -iname *.hpp -o -iname *.cpp -o -iname *.c | xargs clang-format-14 -i
32 changes: 10 additions & 22 deletions mrpt_map_server/include/mrpt_map_server/map_server_node.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,10 +38,8 @@ class MapServer : public rclcpp::Node

std::string frame_id_ = "map";

rclcpp::Service<nav_msgs::srv::GetMap>::SharedPtr
m_service_map; //!< service for map server
nav_msgs::srv::GetMap::Response
m_response_ros; //!< response from the map server
rclcpp::Service<nav_msgs::srv::GetMap>::SharedPtr m_service_map; //!< service for map server
nav_msgs::srv::GetMap::Response m_response_ros; //!< response from the map server

/// metric map: will be used whatever is the incoming map format.
mp2p_icp::metric_map_t theMap_;
Expand Down Expand Up @@ -98,34 +96,24 @@ class MapServer : public rclcpp::Node

// clang-format on

sensor_msgs::msg::PointCloud2 pointmap_layer_to_msg(
const mrpt::maps::CPointsMap::Ptr& pts);
sensor_msgs::msg::PointCloud2 pointmap_layer_to_msg(const mrpt::maps::CPointsMap::Ptr& pts);

// Services:
rclcpp::Service<mrpt_nav_interfaces::srv::GetLayers>::SharedPtr
srvMapLayers_;
rclcpp::Service<mrpt_nav_interfaces::srv::GetLayers>::SharedPtr srvMapLayers_;

void srv_map_layers(
const std::shared_ptr<mrpt_nav_interfaces::srv::GetLayers::Request> req,
std::shared_ptr<mrpt_nav_interfaces::srv::GetLayers::Response> resp);

rclcpp::Service<mrpt_nav_interfaces::srv::GetGridmapLayer>::SharedPtr
srvGetGrid_;
rclcpp::Service<mrpt_nav_interfaces::srv::GetGridmapLayer>::SharedPtr srvGetGrid_;

void srv_get_gridmap(
const std::shared_ptr<
mrpt_nav_interfaces::srv::GetGridmapLayer::Request>
req,
std::shared_ptr<mrpt_nav_interfaces::srv::GetGridmapLayer::Response>
resp);
const std::shared_ptr<mrpt_nav_interfaces::srv::GetGridmapLayer::Request> req,
std::shared_ptr<mrpt_nav_interfaces::srv::GetGridmapLayer::Response> resp);

rclcpp::Service<mrpt_nav_interfaces::srv::GetPointmapLayer>::SharedPtr
srvGetPoints_;
rclcpp::Service<mrpt_nav_interfaces::srv::GetPointmapLayer>::SharedPtr srvGetPoints_;

void srv_get_pointmap(
const std::shared_ptr<
mrpt_nav_interfaces::srv::GetPointmapLayer::Request>
req,
std::shared_ptr<mrpt_nav_interfaces::srv::GetPointmapLayer::Response>
resp);
const std::shared_ptr<mrpt_nav_interfaces::srv::GetPointmapLayer::Request> req,
std::shared_ptr<mrpt_nav_interfaces::srv::GetPointmapLayer::Response> resp);
};
87 changes: 27 additions & 60 deletions mrpt_map_server/src/map_server_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,15 +46,12 @@ void MapServer::init()
std::string map_yaml_file;
this->declare_parameter<std::string>("map_yaml_file", "");
this->get_parameter("map_yaml_file", map_yaml_file);
RCLCPP_INFO(
this->get_logger(), "map_yaml_file name: '%s'", map_yaml_file.c_str());
RCLCPP_INFO(this->get_logger(), "map_yaml_file name: '%s'", map_yaml_file.c_str());

std::string mrpt_metricmap_file;
this->declare_parameter<std::string>("mrpt_metricmap_file", "");
this->get_parameter("mrpt_metricmap_file", mrpt_metricmap_file);
RCLCPP_INFO(
this->get_logger(), "mrpt_metricmap_file name: '%s'",
mrpt_metricmap_file.c_str());
RCLCPP_INFO(this->get_logger(), "mrpt_metricmap_file name: '%s'", mrpt_metricmap_file.c_str());

auto lck = mrpt::lockHelper(theMapMtx_);

Expand Down Expand Up @@ -94,15 +91,13 @@ void MapServer::init()
ASSERT_FILE_EXISTS_(mm_file);

RCLCPP_INFO_STREAM(
this->get_logger(),
"Loading metric_map_t map from '" << mm_file << "' ...");
this->get_logger(), "Loading metric_map_t map from '" << mm_file << "' ...");

bool mapReadOk = theMap_.load_from_file(mm_file);
ASSERT_(mapReadOk);

RCLCPP_INFO_STREAM(
this->get_logger(),
"Loaded map contents: " << theMap_.contents_summary());
this->get_logger(), "Loaded map contents: " << theMap_.contents_summary());
}

this->declare_parameter<std::string>("frame_id", frame_id_);
Expand All @@ -111,13 +106,11 @@ void MapServer::init()

this->declare_parameter<std::string>("pub_mm_topic", pub_mm_topic_);
this->get_parameter("pub_mm_topic", pub_mm_topic_);
RCLCPP_INFO(
this->get_logger(), "pub_mm_topic: '%s'", pub_mm_topic_.c_str());
RCLCPP_INFO(this->get_logger(), "pub_mm_topic: '%s'", pub_mm_topic_.c_str());

this->declare_parameter<std::string>("service_map", service_map_str_);
this->get_parameter("service_map", service_map_str_);
RCLCPP_INFO(
this->get_logger(), "service_map: '%s'", service_map_str_.c_str());
RCLCPP_INFO(this->get_logger(), "service_map: '%s'", service_map_str_.c_str());

srvMapLayers_ = this->create_service<mrpt_nav_interfaces::srv::GetLayers>(
this->get_fully_qualified_name() + "/get_layers"s,
Expand All @@ -126,21 +119,17 @@ void MapServer::init()
mrpt_nav_interfaces::srv::GetLayers::Response::SharedPtr res)
{ srv_map_layers(req, res); });

srvGetGrid_ = this->create_service<
mrpt_nav_interfaces::srv::GetGridmapLayer>(
srvGetGrid_ = this->create_service<mrpt_nav_interfaces::srv::GetGridmapLayer>(
this->get_fully_qualified_name() + "/get_grid_layer"s,
[this](
const mrpt_nav_interfaces::srv::GetGridmapLayer::Request::SharedPtr
req,
const mrpt_nav_interfaces::srv::GetGridmapLayer::Request::SharedPtr req,
mrpt_nav_interfaces::srv::GetGridmapLayer::Response::SharedPtr res)
{ srv_get_gridmap(req, res); });

srvGetPoints_ = this->create_service<
mrpt_nav_interfaces::srv::GetPointmapLayer>(
srvGetPoints_ = this->create_service<mrpt_nav_interfaces::srv::GetPointmapLayer>(
this->get_fully_qualified_name() + "/get_pointcloud_layer"s,
[this](
const mrpt_nav_interfaces::srv::GetPointmapLayer::Request::SharedPtr
req,
const mrpt_nav_interfaces::srv::GetPointmapLayer::Request::SharedPtr req,
mrpt_nav_interfaces::srv::GetPointmapLayer::Response::SharedPtr res)
{ srv_get_pointmap(req, res); });
}
Expand Down Expand Up @@ -178,9 +167,8 @@ void MapServer::publish_map()
// 2.1) for any map, publish it in mrpt binary form:
if (pubLayers_.count(layerName) == 0)
{
pubLayers_[layerName].pub =
this->create_publisher<mrpt_msgs::msg::GenericObject>(
pub_mm_topic_ + "/"s + layerName, QoS);
pubLayers_[layerName].pub = this->create_publisher<mrpt_msgs::msg::GenericObject>(
pub_mm_topic_ + "/"s + layerName, QoS);
}

{
Expand All @@ -191,9 +179,7 @@ void MapServer::publish_map()

// 2.2) publish as ROS standard msgs, if applicable too:
// Is it a pointcloud?
if (auto pts =
std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(layerMap);
pts)
if (auto pts = std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(layerMap); pts)
{
if (pubPointMaps_.count(layerName) == 0)
{
Expand All @@ -203,17 +189,14 @@ void MapServer::publish_map()
}

{
const sensor_msgs::msg::PointCloud2 msg_pts =
pointmap_layer_to_msg(pts);
const sensor_msgs::msg::PointCloud2 msg_pts = pointmap_layer_to_msg(pts);

pubPointMaps_[layerName].pub->publish(msg_pts);
}
}

// Is it a voxelmap?
if (auto vxl =
std::dynamic_pointer_cast<mrpt::maps::CVoxelMap>(layerMap);
vxl)
if (auto vxl = std::dynamic_pointer_cast<mrpt::maps::CVoxelMap>(layerMap); vxl)
{
// Render in RVIZ as occupied voxels=points:
mrpt::maps::CSimplePointsMap::Ptr pts = vxl->getOccupiedVoxels();
Expand All @@ -233,21 +216,16 @@ void MapServer::publish_map()
}

// Is it a grid map?
if (auto grid =
std::dynamic_pointer_cast<mrpt::maps::COccupancyGridMap2D>(
layerMap);
grid)
if (auto grid = std::dynamic_pointer_cast<mrpt::maps::COccupancyGridMap2D>(layerMap); grid)
{
if (pubGridMaps_.count(layerName) == 0)
{
pubGridMaps_[layerName].pub =
this->create_publisher<nav_msgs::msg::OccupancyGrid>(
pub_mm_topic_ + "/"s + layerName + "_gridmap"s, QoS);
pubGridMaps_[layerName].pub = this->create_publisher<nav_msgs::msg::OccupancyGrid>(
pub_mm_topic_ + "/"s + layerName + "_gridmap"s, QoS);

pubGridMapsMetaData_[layerName].pub =
this->create_publisher<nav_msgs::msg::MapMetaData>(
pub_mm_topic_ + "/"s + layerName + "_gridmap_metadata"s,
QoS);
pub_mm_topic_ + "/"s + layerName + "_gridmap_metadata"s, QoS);
}

{
Expand Down Expand Up @@ -277,15 +255,12 @@ void MapServer::srv_map_layers(
(void)req;

resp->layers.clear();
for (const auto& [layerName, _] : theMap_.layers)
resp->layers.push_back(layerName);
for (const auto& [layerName, _] : theMap_.layers) resp->layers.push_back(layerName);
}

void MapServer::srv_get_gridmap(
const std::shared_ptr<mrpt_nav_interfaces::srv::GetGridmapLayer::Request>
req,
const std::shared_ptr<mrpt_nav_interfaces::srv::GetGridmapLayer::Response>
resp)
const std::shared_ptr<mrpt_nav_interfaces::srv::GetGridmapLayer::Request> req,
const std::shared_ptr<mrpt_nav_interfaces::srv::GetGridmapLayer::Response> resp)
{
auto lck = mrpt::lockHelper(theMapMtx_);

Expand All @@ -307,8 +282,7 @@ void MapServer::srv_get_gridmap(
}

void MapServer::srv_get_pointmap(
const std::shared_ptr<mrpt_nav_interfaces::srv::GetPointmapLayer::Request>
req,
const std::shared_ptr<mrpt_nav_interfaces::srv::GetPointmapLayer::Request> req,
std::shared_ptr<mrpt_nav_interfaces::srv::GetPointmapLayer::Response> resp)
{
auto lck = mrpt::lockHelper(theMapMtx_);
Expand Down Expand Up @@ -339,29 +313,22 @@ sensor_msgs::msg::PointCloud2 MapServer::pointmap_layer_to_msg(

sensor_msgs::msg::PointCloud2 msg_pts;

if (auto* xyzirt =
dynamic_cast<const mrpt::maps::CPointsMapXYZIRT*>(pts.get());
xyzirt)
if (auto* xyzirt = dynamic_cast<const mrpt::maps::CPointsMapXYZIRT*>(pts.get()); xyzirt)
{
mrpt::ros2bridge::toROS(*xyzirt, msg_header, msg_pts);
}
else if (auto* xyzi =
dynamic_cast<const mrpt::maps::CPointsMapXYZI*>(pts.get());
xyzi)
else if (auto* xyzi = dynamic_cast<const mrpt::maps::CPointsMapXYZI*>(pts.get()); xyzi)
{
mrpt::ros2bridge::toROS(*xyzi, msg_header, msg_pts);
}
else if (auto* sPts =
dynamic_cast<const mrpt::maps::CSimplePointsMap*>(pts.get());
sPts)
else if (auto* sPts = dynamic_cast<const mrpt::maps::CSimplePointsMap*>(pts.get()); sPts)
{
mrpt::ros2bridge::toROS(*sPts, msg_header, msg_pts);
}
else
{
THROW_EXCEPTION_FMT(
"Unexpected point cloud class: '%s'",
pts->GetRuntimeClass()->className);
"Unexpected point cloud class: '%s'", pts->GetRuntimeClass()->className);
}

return msg_pts;
Expand Down
9 changes: 3 additions & 6 deletions mrpt_msgs_bridge/include/mrpt_msgs_bridge/beacon.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,26 +26,23 @@ namespace mrpt_msgs_bridge
* \sa mrpt2ros
*/
bool fromROS(
const mrpt_msgs::msg::ObservationRangeBeacon _msg,
const mrpt::poses::CPose3D& _pose,
const mrpt_msgs::msg::ObservationRangeBeacon _msg, const mrpt::poses::CPose3D& _pose,
mrpt::obs::CObservationBeaconRanges& _obj);

/** MRPT->ROS2: Takes a CObservationBeaconRanges and outputs range data in
* mrpt_msgs::ObservationRangeBeacon \return true on sucessful conversion, false
* on any error. \sa ros2mrpt
*/
bool toROS(
const mrpt::obs::CObservationBeaconRanges& _obj,
mrpt_msgs::msg::ObservationRangeBeacon& _msg);
const mrpt::obs::CObservationBeaconRanges& _obj, mrpt_msgs::msg::ObservationRangeBeacon& _msg);

/** MRPT->ROS2: Takes a CObservationBeaconRanges and outputs range data in
* mrpt_msgs::ObservationRangeBeacon + the relative pose of the range sensor wrt
* base_link \return true on sucessful conversion, false on any error. \sa
* ros2mrpt
*/
bool toROS(
const mrpt::obs::CObservationBeaconRanges& _obj,
mrpt_msgs::msg::ObservationRangeBeacon& _msg,
const mrpt::obs::CObservationBeaconRanges& _obj, mrpt_msgs::msg::ObservationRangeBeacon& _msg,
geometry_msgs::msg::Pose& _pose);

/** @} */
Expand Down
9 changes: 3 additions & 6 deletions mrpt_msgs_bridge/include/mrpt_msgs_bridge/landmark.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,7 @@ namespace mrpt_msgs_bridge
* true on sucessful conversion, false on any error. \sa mrpt2ros
*/
bool fromROS(
const mrpt_msgs::msg::ObservationRangeBearing& _msg,
const mrpt::poses::CPose3D& _pose,
const mrpt_msgs::msg::ObservationRangeBearing& _msg, const mrpt::poses::CPose3D& _pose,
mrpt::obs::CObservationBearingRange& _obj);

/** MRPT->ROS2: Takes a CObservationBearingRange and outputs range data in
Expand All @@ -41,8 +40,7 @@ bool fromROS(
* \sa ros2mrpt
*/
bool toROS(
const mrpt::obs::CObservationBearingRange& _obj,
mrpt_msgs::msg::ObservationRangeBearing& _msg);
const mrpt::obs::CObservationBearingRange& _obj, mrpt_msgs::msg::ObservationRangeBearing& _msg);

/** MRPT->ROS2: Takes a CObservationBearingRange and outputs range data in
* mrpt_msgs::ObservationRangeBearing + the relative pose of the range sensor
Expand All @@ -51,8 +49,7 @@ bool toROS(
* \sa ros2mrpt
*/
bool toROS(
const mrpt::obs::CObservationBearingRange& _obj,
mrpt_msgs::msg::ObservationRangeBearing& _msg,
const mrpt::obs::CObservationBearingRange& _obj, mrpt_msgs::msg::ObservationRangeBearing& _msg,
geometry_msgs::msg::Pose& sensorPose);

/** @} */
Expand Down
6 changes: 2 additions & 4 deletions mrpt_msgs_bridge/include/mrpt_msgs_bridge/marker_msgs.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,13 +31,11 @@ namespace mrpt_msgs_bridge
// official repos, so we need to build it here within ROS.

bool fromROS(
const marker_msgs::msg::MarkerDetection& _msg,
const mrpt::poses::CPose3D& sensorPoseOnRobot,
const marker_msgs::msg::MarkerDetection& _msg, const mrpt::poses::CPose3D& sensorPoseOnRobot,
mrpt::obs::CObservationBearingRange& _obj);

bool fromROS(
const marker_msgs::msg::MarkerDetection& _msg,
const mrpt::poses::CPose3D& sensorPoseOnRobot,
const marker_msgs::msg::MarkerDetection& _msg, const mrpt::poses::CPose3D& sensorPoseOnRobot,
mrpt::obs::CObservationBeaconRanges& _obj);

} // namespace mrpt_msgs_bridge
12 changes: 4 additions & 8 deletions mrpt_msgs_bridge/include/mrpt_msgs_bridge/network_of_poses.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,12 +27,10 @@ namespace mrpt_msgs_bridge

// TODO - convert these methods into a common polymorphic method
void toROS(
const mrpt::graphs::CNetworkOfPoses2D& mrpt_graph,
mrpt_msgs::msg::NetworkOfPoses& ros_graph);
const mrpt::graphs::CNetworkOfPoses2D& mrpt_graph, mrpt_msgs::msg::NetworkOfPoses& ros_graph);

void toROS(
const mrpt::graphs::CNetworkOfPoses3D& mrpt_graph,
mrpt_msgs::msg::NetworkOfPoses& ros_graph);
const mrpt::graphs::CNetworkOfPoses3D& mrpt_graph, mrpt_msgs::msg::NetworkOfPoses& ros_graph);

void toROS(
const mrpt::graphs::CNetworkOfPoses2DInf& mrpt_graph,
Expand Down Expand Up @@ -61,12 +59,10 @@ void toROS(
*/
/**\{ */
void fromROS(
const mrpt::graphs::CNetworkOfPoses2D& mrpt_graph,
mrpt_msgs::msg::NetworkOfPoses& ros_graph);
const mrpt::graphs::CNetworkOfPoses2D& mrpt_graph, mrpt_msgs::msg::NetworkOfPoses& ros_graph);

void fromROS(
const mrpt::graphs::CNetworkOfPoses3D& mrpt_graph,
mrpt_msgs::msg::NetworkOfPoses& ros_graph);
const mrpt::graphs::CNetworkOfPoses3D& mrpt_graph, mrpt_msgs::msg::NetworkOfPoses& ros_graph);

void fromROS(
const mrpt_msgs::msg::NetworkOfPoses& ros_graph,
Expand Down
Loading

0 comments on commit 3d7521c

Please sign in to comment.