Skip to content

Commit

Permalink
Fix cpplint test in motion_computation to support CI/CD (#2405)
Browse files Browse the repository at this point in the history
* fix white space

* clang format

* add 2 space and order headers

* fix more

* try again

* reuse cp clang and turn off include order

* Add source link for IncludeCategories
  • Loading branch information
MishkaMN committed Jun 14, 2024
1 parent ccbb4c3 commit 2fee8dc
Show file tree
Hide file tree
Showing 16 changed files with 175 additions and 121 deletions.
47 changes: 47 additions & 0 deletions motion_computation/.clang-format
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
---
# ROS 2 C++ style guidelines
# Reference: https://github.com/ament/ament_lint/blob/rolling/ament_clang_format/ament_clang_format/configuration/.clang-format
Language: Cpp
BasedOnStyle: Google

AccessModifierOffset: -2
AlignAfterOpenBracket: AlwaysBreak
BraceWrapping:
AfterClass: true
AfterFunction: true
AfterNamespace: true
AfterStruct: true
AfterEnum: true
BreakBeforeBraces: Custom
ColumnLimit: 100
ConstructorInitializerIndentWidth: 0
ContinuationIndentWidth: 2
DerivePointerAlignment: false
PointerAlignment: Middle
ReflowComments: false
SpacesBeforeTrailingComments: 2
IncludeCategories:
# Originally from: https://github.com/usdot-fhwa-stol/autoware.auto/blob/carma-system-4.5.0/AutowareAuto/.clang-format
# Main header (e.g. foo.hpp for foo.cpp) automatically assigned priority zero

# Rules are processed in order, the first match assigns the priority, so more general rules come last

# C System headers
- Regex: '^<.*\.h>'
Priority: 1
# Eigen headers are not std C++ headers
- Regex: '<Eigen/([A-Za-z0-9\Q/-_\E])+>'
Priority: 3
# Headers in <> without extension; e.g. C++ standard
- Regex: '<([A-Za-z0-9\Q/-_\E])+>'
Priority: 2
# Messages
- Regex: '.*_msgs/.*\.hpp'
Priority: 4
# Headers in "" with file extension; e.g. from the same or another package
- Regex: '"([A-Za-z0-9.\Q/-_\E])+"'
Priority: 3
# Other Packages
- Regex: '^<.*/.*\.h.*>'
Priority: 3
IncludeBlocks: Regroup
4 changes: 4 additions & 0 deletions motion_computation/CPPLINT.cfg
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
# Disable cpplint's include_order check. The checks are inconsistent with ROS 2
# header files, so we are disabling it until we know more about how the order
# and C vs. C++ files are validated
filter=-build/include_order
Original file line number Diff line number Diff line change
Expand Up @@ -18,16 +18,18 @@
#include <lanelet2_extension/projection/local_frame_projector.h>
#include <tf2/LinearMath/Quaternion.h>
#include <tf2/LinearMath/Vector3.h>

#include <tuple>
#include <utility>

#include <rclcpp/time.hpp>

#include <carma_perception_msgs/msg/external_object.hpp>
#include <carma_perception_msgs/msg/predicted_state.hpp>
#include <geometry_msgs/msg/quaternion.hpp>
#include <rclcpp/time.hpp>
#include <tuple>
#include <utility>

namespace motion_computation
{

namespace conversion
{
namespace impl
Expand All @@ -38,11 +40,12 @@ namespace impl
* \param curr_pt current point
* \param prev_pt prev_pt. this point is recorded in the state
* \param prev_time_stamp prev_pt's time stamp. This time is recorded in the state
* \param curr_time_stamp The timestamp of the second point when used to compute velocity at prev point
* \param curr_time_stamp The timestamp of the second point when used to compute velocity at prev
* point
* \param prev_yaw A previous yaw value in radians to use if the two provided points are equivalent
* \return std::pair<carma_perception_msgs::msg::PredictedState,double> where the first element is the prediction
* including linear velocity, last_time, orientation filled in and the second element is the yaw in radians used to
* compute the orientation
* \return std::pair<carma_perception_msgs::msg::PredictedState,double> where the first element is
* the prediction including linear velocity, last_time, orientation filled in and the second
* element is the yaw in radians used to compute the orientation
*/
std::pair<carma_perception_msgs::msg::PredictedState, double> composePredictedState(
const tf2::Vector3 & curr_pt, const tf2::Vector3 & prev_pt, const rclcpp::Time & prev_time_stamp,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,20 +18,21 @@
#include <lanelet2_core/primitives/GPSPoint.h>
#include <lanelet2_extension/projection/local_frame_projector.h>
#include <tf2/LinearMath/Quaternion.h>

#include <string>
#include <vector>

#include <rclcpp/rclcpp.hpp>

#include <carma_perception_msgs/msg/external_object.hpp>
#include <carma_v2x_msgs/msg/psm.hpp>
#include <geometry_msgs/msg/pose.hpp>
#include <geometry_msgs/msg/pose_with_covariance.hpp>
#include <rclcpp/rclcpp.hpp>
#include <string>
#include <vector>

namespace motion_computation
{

namespace conversion
{

// Namespace for functionality not meant to be part of public API but valuable
// to unit test in isolation
namespace impl
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,19 +17,20 @@

#include <lanelet2_extension/projection/local_frame_projector.h>
#include <tf2/LinearMath/Quaternion.h>

#include <string>

#include <rclcpp/rclcpp.hpp>

#include <carma_perception_msgs/msg/external_object.hpp>
#include <carma_v2x_msgs/msg/bsm.hpp>
#include <carma_v2x_msgs/msg/mobility_path.hpp>
#include <carma_v2x_msgs/msg/psm.hpp>
#include <rclcpp/rclcpp.hpp>
#include <string>

namespace motion_computation
{

namespace conversion
{

void convert(
const carma_v2x_msgs::msg::PSM & in_msg, carma_perception_msgs::msg::ExternalObject & out_msg,
const std::string & map_frame_id, double pred_period, double pred_step_size,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@

namespace motion_computation
{

/**
* \brief Stuct containing the algorithm configuration values for motion_computation
*/
Expand All @@ -29,11 +28,11 @@ struct Config
double prediction_time_step = 0.1; // Time between predicted states (in seconds)
double mobility_path_time_step =
0.1; // Time between received mobility path predicted states (in seconds)
double prediction_period = 2.0; // Period of prediction (in seconds)
double cv_x_accel_noise = 9.0; // CV Model X-Axis Acceleration Noise
double cv_y_accel_noise = 9.0; // CV Model Y-Axis Acceleration Noise
double prediction_process_noise_max =
1000.0; // Maximum expected process noise; used for mapping noise to confidence in [0,1] range
double prediction_period = 2.0; // Period of prediction (in seconds)
double cv_x_accel_noise = 9.0; // CV Model X-Axis Acceleration Noise
double cv_y_accel_noise = 9.0; // CV Model Y-Axis Acceleration Noise
double prediction_process_noise_max = 1000.0; // Maximum expected process noise; used for mapping
// noise to confidence in [0,1] range
double prediction_confidence_drop_rate =
0.95; // Percentage of initial confidence to propagate to next time step

Expand All @@ -57,7 +56,7 @@ struct Config
// will occur (objects may be duplicated)
bool enable_sensor_processing = false;

// True if CTRV motion model should be used for the object type.
// True if CTRV motion model should be used for the object type.
// False, if CV should be used for all following booleans
bool enable_ctrv_for_unknown_obj = true;
bool enable_ctrv_for_motorcycle_obj = true;
Expand All @@ -82,8 +81,10 @@ struct Config
<< "enable_sensor_processing: " << c.enable_sensor_processing << std::endl
<< "enable_ctrv_for_unknown_obj: " << c.enable_ctrv_for_unknown_obj << std::endl
<< "enable_ctrv_for_motorcycle_obj: " << c.enable_ctrv_for_motorcycle_obj << std::endl
<< "enable_ctrv_for_small_vehicle_obj: " << c.enable_ctrv_for_small_vehicle_obj << std::endl
<< "enable_ctrv_for_large_vehicle_obj: " << c.enable_ctrv_for_large_vehicle_obj << std::endl
<< "enable_ctrv_for_small_vehicle_obj: " << c.enable_ctrv_for_small_vehicle_obj
<< std::endl
<< "enable_ctrv_for_large_vehicle_obj: " << c.enable_ctrv_for_large_vehicle_obj
<< std::endl
<< "enable_ctrv_for_pedestrian_obj: " << c.enable_ctrv_for_pedestrian_obj << std::endl
<< "}" << std::endl;
return output;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,21 +17,21 @@

#include <lanelet2_extension/projection/local_frame_projector.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <carma_perception_msgs/msg/external_object_list.hpp>
#include <carma_ros2_utils/carma_lifecycle_node.hpp>
#include <carma_v2x_msgs/msg/mobility_path.hpp>
#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/string.hpp>

#include <functional>
#include <vector>

#include "motion_computation/motion_computation_config.hpp"
#include "motion_computation/motion_computation_worker.hpp"
#include <carma_ros2_utils/carma_lifecycle_node.hpp>
#include <rclcpp/rclcpp.hpp>

#include <carma_perception_msgs/msg/external_object_list.hpp>
#include <carma_v2x_msgs/msg/mobility_path.hpp>
#include <std_msgs/msg/string.hpp>

namespace motion_computation
{

/**
* \class MotionComputationNode
* \brief The class responsible for publishing external object predictions
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,25 +19,26 @@
#include <lanelet2_extension/projection/local_frame_projector.h>
#include <tf2/LinearMath/Transform.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <carma_perception_msgs/msg/external_object.hpp>
#include <carma_perception_msgs/msg/external_object_list.hpp>
#include <carma_v2x_msgs/msg/bsm.hpp>
#include <carma_v2x_msgs/msg/mobility_path.hpp>
#include <carma_v2x_msgs/msg/psm.hpp>
#include <motion_predict/motion_predict.hpp>
#include <motion_predict/predict_ctrv.hpp>
#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/string.hpp>

#include <functional>
#include <memory>
#include <string>
#include <tuple>
#include <unordered_map>

#include <motion_predict/motion_predict.hpp>
#include <motion_predict/predict_ctrv.hpp>
#include <rclcpp/rclcpp.hpp>

#include <carma_perception_msgs/msg/external_object.hpp>
#include <carma_perception_msgs/msg/external_object_list.hpp>
#include <carma_v2x_msgs/msg/bsm.hpp>
#include <carma_v2x_msgs/msg/mobility_path.hpp>
#include <carma_v2x_msgs/msg/psm.hpp>
#include <std_msgs/msg/string.hpp>

namespace motion_computation
{

/**
* \class MotionComputationWorker
* \brief The class containing the primary business logic for the Motion Computation Package
Expand Down Expand Up @@ -74,8 +75,9 @@ class MotionComputationWorker
bool enable_sensor_processing, bool enable_bsm_processing, bool enable_psm_processing,
bool enable_mobility_path_processing);
void setDetectionMotionModelFlags(
bool enable_ctrv_for_unknown_obj, bool enable_ctrv_for_motorcycle_obj, bool enable_ctrv_for_small_vehicle_obj,
bool enable_ctrv_for_large_vehicle_obj, bool enable_ctrv_for_pedestrian_obj);
bool enable_ctrv_for_unknown_obj, bool enable_ctrv_for_motorcycle_obj,
bool enable_ctrv_for_small_vehicle_obj, bool enable_ctrv_for_large_vehicle_obj,
bool enable_ctrv_for_pedestrian_obj);

// callbacks
void mobilityPathCallback(const carma_v2x_msgs::msg::MobilityPath::UniquePtr msg);
Expand All @@ -91,8 +93,8 @@ class MotionComputationWorker
void georeferenceCallback(const std_msgs::msg::String::UniquePtr msg);

/**
* \brief Converts from MobilityPath's predicted points in ECEF to local map and other fields in an ExternalObject
* object
* \brief Converts from MobilityPath's predicted points in ECEF to local map and other fields in
* an ExternalObject object
* \param msg MobilityPath message to convert
* \return ExternalObject object
*/
Expand All @@ -101,9 +103,9 @@ class MotionComputationWorker

/**
* \brief Appends external objects list behind base_objects. This does not do sensor fusion.
* When doing so, it drops the predictions points that start before the first prediction is sensor list.
* And interpolates the remaining predictions points to match the timestep using its average speed
* between points
* When doing so, it drops the predictions points that start before the first prediction is
* sensor list. And interpolates the remaining predictions points to match the timestep using its
* average speed between points
* \param base_objects object detections to append to and synchronize with
* \param new_objects new objects to add and be synchronized
* \return append and synchronized list of external objects
Expand All @@ -113,9 +115,10 @@ class MotionComputationWorker
carma_perception_msgs::msg::ExternalObjectList new_objects) const;

/*!
* \brief It cuts ExternalObject's prediction points before the time_to_match. And uses the average
* velocity in its predictions to match the starting point to the point it would have crossed at time_to_match
* It uses mobility_path_time_step between prediction points to interpolate.
* \brief It cuts ExternalObject's prediction points before the time_to_match. And uses the
* average velocity in its predictions to match the starting point to the point it would have
* crossed at time_to_match It uses mobility_path_time_step between prediction points to
* interpolate.
* \param path External object with predictions to modify
* \param time_to_match time stamp to have the object start at
* \return carma_perception_msgs::msg::ExternalObject
Expand Down Expand Up @@ -149,7 +152,7 @@ class MotionComputationWorker
bool enable_ctrv_for_small_vehicle_obj_ = true;
bool enable_ctrv_for_large_vehicle_obj_ = true;
bool enable_ctrv_for_pedestrian_obj_ = false;

// Map frame
std::string map_frame_id_ = "map";

Expand Down
11 changes: 5 additions & 6 deletions motion_computation/src/bsm_to_external_object_convertor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,20 +12,19 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <carma_perception_msgs/msg/external_object.hpp>
#include <motion_computation/impl/psm_to_external_object_helpers.hpp>
#include <motion_computation/message_conversions.hpp>

#include <algorithm>
#include <string>
#include <vector>

#include <motion_computation/impl/psm_to_external_object_helpers.hpp>
#include <motion_computation/message_conversions.hpp>

#include <carma_perception_msgs/msg/external_object.hpp>

namespace motion_computation
{

namespace conversion
{

void convert(
const carma_v2x_msgs::msg::BSM & in_msg, carma_perception_msgs::msg::ExternalObject & out_msg,
const std::string & map_frame_id, double pred_period, double pred_step_size,
Expand Down
7 changes: 2 additions & 5 deletions motion_computation/src/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,14 +12,11 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <rclcpp/rclcpp.hpp>

#include <memory>

#include "motion_computation/motion_computation_node.hpp"
#include <rclcpp/rclcpp.hpp>

int main(int argc, char ** argv)
{
int main(int argc, char **argv) {
rclcpp::init(argc, argv);

auto node = std::make_shared<motion_computation::MotionComputationNode>(rclcpp::NodeOptions());
Expand Down
Loading

0 comments on commit 2fee8dc

Please sign in to comment.