Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

CI integration #154

Merged
merged 25 commits into from
May 15, 2024
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
Show all changes
25 commits
Select commit Hold shift + click to select a range
0510b48
create workflow "test.yml"
apmilko May 13, 2024
b3aef12
add hook "check-added-large-files", init pre-commit action
apmilko May 13, 2024
7c4a7bc
update hook "check-added-large-files"
apmilko May 13, 2024
c24cb3b
update hook "check-merge-conflict"
apmilko May 13, 2024
33500ef
add hook "check-xml"
apmilko May 13, 2024
53db069
add hook "check-toml"
apmilko May 13, 2024
d100c8e
add hook "end-of-file-fixer"
apmilko May 13, 2024
611bd83
add hook "mixed-line-ending"
apmilko May 13, 2024
03fc81d
add hook "trailing-whitespace"
apmilko May 13, 2024
521187f
add hook "cmake-format", "cmake-lint"
apmilko May 13, 2024
5f01378
add hook "ruff", "ruff-format"
apmilko May 13, 2024
caad4c2
add hook "clang-format"
apmilko May 13, 2024
ee83f72
update hook "clang-format"
apmilko May 13, 2024
709b4c8
add hook "yamllint"
apmilko May 13, 2024
8ce7630
add hook "check-json", "check-yaml", fix .yaml files
apmilko May 13, 2024
0798261
Merge branch 'master' into apmilko-ci
apmilko May 15, 2024
c80b7db
apply pre-commit to last merge commit
apmilko May 15, 2024
391c1b5
fix pointer alignment in hook "clang-format"
apmilko May 15, 2024
57c1539
set new max line-length for ".yamllint-config.yaml"
apmilko May 15, 2024
d1c8511
add config ".cmake-format.py" for hook "cmake-format"
apmilko May 15, 2024
c6fcd41
update ".clang-format"
apmilko May 15, 2024
d2234e5
update ".clang-format"
apmilko May 15, 2024
a1afea9
Merge branch 'master' into apmilko-ci
apmilko May 15, 2024
3437c5b
Add CI badge to README.md
apmilko May 15, 2024
fa61773
run pre-commit after last merge
apmilko May 15, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions .clang-format
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@ ColumnLimit: 100
CompactNamespaces: false
IndentWidth: 4
NamespaceIndentation: None
DerivePointerAlignment: false
PointerAlignment: Left
SortIncludes: false
SpaceAfterTemplateKeyword: false
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,9 +16,9 @@ class CameraTracker {
public:
CameraTracker(int marker_count);

void Update(const std::vector<int> &ids, const std::vector<Transform> &transforms);
void Update(const std::vector<int>& ids, const std::vector<Transform>& transforms);

const std::optional<Transform> &GetTransformToAnchor(int from_id) const;
const std::optional<Transform>& GetTransformToAnchor(int from_id) const;

Pose GetPose();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ edge
@param last_node last node in shortest path from start_node
*/
void Dijkstra(
int nodes_count, int start_node, std::vector<double> &distance, std::vector<int> &last_node,
const std::function<double(int, int)> &get_weight);
int nodes_count, int start_node, std::vector<double>& distance, std::vector<int>& last_node,
const std::function<double(int, int)>& get_weight);

} // namespace rosaruco
Original file line number Diff line number Diff line change
Expand Up @@ -11,21 +11,21 @@ class Transform {
tf2::Vector3 translation_;

public:
Transform(const tf2::Quaternion &rotation, const tf2::Vector3 &translation);
Transform(const tf2::Quaternion& rotation, const tf2::Vector3& translation);

tf2::Vector3 Apply(const tf2::Vector3 &v) const;
tf2::Vector3 Apply(const tf2::Vector3& v) const;

tf2::Vector3 operator()(const tf2::Vector3 &v) const;
tf2::Vector3 operator()(const tf2::Vector3& v) const;

const tf2::Quaternion &GetRotation() const;
const tf2::Quaternion& GetRotation() const;

const tf2::Vector3 &GetTranslation() const;
const tf2::Vector3& GetTranslation() const;

void SetRotation(const tf2::Quaternion &r);
void SetRotation(const tf2::Quaternion& r);

void SetTranslation(const tf2::Vector3 &t);
void SetTranslation(const tf2::Vector3& t);

Transform operator*(const Transform &other) const;
Transform operator*(const Transform& other) const;

Transform Inverse() const;
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,12 +6,12 @@

namespace rosaruco {

visualization_msgs::msg::Marker GetMarker(const Transform &t, double size);
visualization_msgs::msg::Marker GetMarker(const Transform& t, double size);

visualization_msgs::msg::Marker GetLabel(int id, const tf2::Vector3 &p, double size);
visualization_msgs::msg::Marker GetLabel(int id, const tf2::Vector3& p, double size);

void AddLabeledMarker(
std::vector<visualization_msgs::msg::Marker> &markers, const Transform &t, int id, double size,
std::vector<visualization_msgs::msg::Marker>& markers, const Transform& t, int id, double size,
bool is_visible);

} // namespace rosaruco
4 changes: 2 additions & 2 deletions packages/aruco_localization/src/camera_tracker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ CameraTracker::CameraTracker(int markers_count_) : graph_(markers_count_) {
}

void CameraTracker::Update(
const std::vector<int> &ids, const std::vector<Transform> &from_marker_to_cam) {
const std::vector<int>& ids, const std::vector<Transform>& from_marker_to_cam) {
if (ids.empty()) {
return;
}
Expand Down Expand Up @@ -69,7 +69,7 @@ void CameraTracker::Update(
}
}

const std::optional<Transform> &CameraTracker::GetTransformToAnchor(int from_id) const {
const std::optional<Transform>& CameraTracker::GetTransformToAnchor(int from_id) const {
return to_anchor_[from_id];
}

Expand Down
4 changes: 2 additions & 2 deletions packages/aruco_localization/src/graph_algorithms.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,8 @@
namespace rosaruco {

void Dijkstra(
int nodes_count, int start_node, std::vector<double> &distance, std::vector<int> &prev_node,
const std::function<double(int, int)> &get_weight) {
int nodes_count, int start_node, std::vector<double>& distance, std::vector<int>& prev_node,
const std::function<double(int, int)>& get_weight) {
distance.resize(nodes_count);
fill(distance.begin(), distance.end(), std::numeric_limits<double>::infinity());

Expand Down
16 changes: 8 additions & 8 deletions packages/aruco_localization/src/transform.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,18 +2,18 @@

namespace rosaruco {

Transform::Transform(const tf2::Quaternion &rotation, const tf2::Vector3 &translation)
Transform::Transform(const tf2::Quaternion& rotation, const tf2::Vector3& translation)
: rotation_(rotation.normalized()), translation_(translation) {}

tf2::Vector3 Transform::Apply(const tf2::Vector3 &v) const {
tf2::Vector3 Transform::Apply(const tf2::Vector3& v) const {
auto res = tf2::quatRotate(rotation_, v);
res += translation_;
return res;
}

tf2::Vector3 Transform::operator()(const tf2::Vector3 &v) const { return Apply(v); }
tf2::Vector3 Transform::operator()(const tf2::Vector3& v) const { return Apply(v); }

Transform Transform::operator*(const Transform &other) const {
Transform Transform::operator*(const Transform& other) const {
return Transform((rotation_ * other.rotation_).normalized(), (*this)(other.translation_));
}

Expand All @@ -22,12 +22,12 @@ Transform Transform::Inverse() const {
return Transform(inv_rotation, tf2::quatRotate(inv_rotation, -translation_));
}

const tf2::Quaternion &Transform::GetRotation() const { return rotation_; }
const tf2::Quaternion& Transform::GetRotation() const { return rotation_; }

const tf2::Vector3 &Transform::GetTranslation() const { return translation_; }
const tf2::Vector3& Transform::GetTranslation() const { return translation_; }

void Transform::SetRotation(const tf2::Quaternion &r) { rotation_ = r; }
void Transform::SetRotation(const tf2::Quaternion& r) { rotation_ = r; }

void Transform::SetTranslation(const tf2::Vector3 &t) { translation_ = t; }
void Transform::SetTranslation(const tf2::Vector3& t) { translation_ = t; }

} // namespace rosaruco
10 changes: 5 additions & 5 deletions packages/aruco_localization/src/visualization_helpers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
namespace rosaruco {

visualization_msgs::msg::Marker GetMarker(
const Transform &t, int id, double size, bool is_visible) {
const Transform& t, int id, double size, bool is_visible) {
std::vector<tf2::Vector3> points = {
{0, 0, 0},
{0, size, 0},
Expand All @@ -19,15 +19,15 @@ visualization_msgs::msg::Marker GetMarker(
};

std::transform(
points.begin(), points.end(), points.begin(), [&t](const tf2::Vector3 &v) { return t(v); });
points.begin(), points.end(), points.begin(), [&t](const tf2::Vector3& v) { return t(v); });

points.push_back(points[0]);

visualization_msgs::msg::Marker marker;
marker.points.reserve(points.size());

std::transform(
points.begin(), points.end(), back_inserter(marker.points), [](const tf2::Vector3 &v) {
points.begin(), points.end(), back_inserter(marker.points), [](const tf2::Vector3& v) {
return geometry_msgs::msg::Point().set__x(v[0]).set__y(v[1]).set__z(v[2]);
});

Expand All @@ -47,7 +47,7 @@ visualization_msgs::msg::Marker GetMarker(
return marker;
}

visualization_msgs::msg::Marker GetLabel(int id, const tf2::Vector3 &p, double size) {
visualization_msgs::msg::Marker GetLabel(int id, const tf2::Vector3& p, double size) {
visualization_msgs::msg::Marker marker;
marker.type = visualization_msgs::msg::Marker::TEXT_VIEW_FACING;
marker.action = visualization_msgs::msg::Marker::ADD;
Expand All @@ -65,7 +65,7 @@ visualization_msgs::msg::Marker GetLabel(int id, const tf2::Vector3 &p, double s
}

void AddLabeledMarker(
std::vector<visualization_msgs::msg::Marker> &markers, const Transform &t, int id, double size,
std::vector<visualization_msgs::msg::Marker>& markers, const Transform& t, int id, double size,
bool is_visible) {
markers.push_back(GetMarker(t, id, size, is_visible));
markers.push_back(GetLabel(id, t(tf2::Vector3(size / 2, size / 2, 0)), size / 5));
Expand Down
12 changes: 6 additions & 6 deletions packages/common/tests/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ TEST(fmt, test) {
TEST(exception, constructor) {
try {
throw Exception("Hello, world!");
} catch (const Exception &e) {
} catch (const Exception& e) {
const std::string what = e.what();
ASSERT_EQ(what, "Hello, world!");
}
Expand All @@ -29,7 +29,7 @@ TEST(exception, constructor) {
TEST(exception, like_stream) {
try {
throw Exception() << "x = " << 42;
} catch (const Exception &e) {
} catch (const Exception& e) {
const std::string what = e.what();
ASSERT_EQ(what, "x = 42");
}
Expand All @@ -41,15 +41,15 @@ TEST(verify, to_throw) { EXPECT_THROW(VERIFY(false), Exception); }

TEST(verify, forward) {
const int n = 42;
const int *p = &n;
const int* p = &n;

EXPECT_EQ(VERIFY(p), p);
}

TEST(verify, stream) {
try {
VERIFY_STREAM(false, "x = " << 42);
} catch (const Exception &e) {
} catch (const Exception& e) {
const std::string what = e.what();
EXPECT_TRUE(what.ends_with("x = 42"));
return;
Expand All @@ -61,7 +61,7 @@ TEST(verify, stream) {
TEST(verify, fmt) {
try {
VERIFY_FMT(false, "%s = %d", "x", 42);
} catch (const Exception &e) {
} catch (const Exception& e) {
const std::string what = e.what();
ASSERT_TRUE(what.ends_with("x = 42"));
return;
Expand Down Expand Up @@ -126,7 +126,7 @@ TEST(ArrayAsBinaryIndexedTree, LowerBound) {
}
}

int main(int argc, char *argv[]) {
int main(int argc, char* argv[]) {
::testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}
20 changes: 10 additions & 10 deletions packages/model/src/pybind.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,51 +6,51 @@ namespace py = pybind11;
using namespace truck;

template<typename T>
std::string to_string(const T &obj);
std::string to_string(const T& obj);

template<>
std::string to_string<double>(const double &obj) {
std::string to_string<double>(const double& obj) {
return boost::str(boost::format("%.5d") % obj);
}

template<>
std::string to_string<geom::Angle>(const geom::Angle &obj) {
std::string to_string<geom::Angle>(const geom::Angle& obj) {
return boost::str(boost::format("Angle(%.1d deg)") % obj.degrees());
}

template<>
std::string to_string<model::Steering>(const model::Steering &obj) {
std::string to_string<model::Steering>(const model::Steering& obj) {
return boost::str(
boost::format("Steering(left=%s, right=%s)") % to_string(obj.left) % to_string(obj.right));
}

template<>
std::string to_string<model::WheelVelocity>(const model::WheelVelocity &obj) {
std::string to_string<model::WheelVelocity>(const model::WheelVelocity& obj) {
return boost::str(
boost::format("WheelVelocity(left=%s, right=%s)") % to_string(obj.left) %
to_string(obj.right));
}

template<>
std::string to_string<model::Twist>(const model::Twist &obj) {
std::string to_string<model::Twist>(const model::Twist& obj) {
return boost::str(
boost::format("Twist(curvature=%.5d, velocity=%.5d)") % obj.curvature % obj.velocity);
}

template<>
std::string to_string<model::ServoAngles>(const model::ServoAngles &obj) {
std::string to_string<model::ServoAngles>(const model::ServoAngles& obj) {
return boost::str(
boost::format("ServoAngles(left=%s, right=%s)") % to_string(obj.left) %
to_string(obj.right));
}

template<typename T>
void bind_limits_class(py::module &m, const std::string &name) {
void bind_limits_class(py::module& m, const std::string& name) {
using Class = Limits<T>;
py::class_<Class>(m, name.c_str())
.def_readonly("min", &Class::min)
.def_readonly("max", &Class::max)
.def("__repr__", [name](const Class &obj) {
.def("__repr__", [name](const Class& obj) {
return boost::str(
boost::format("%s(min=%s, max=%s)") % name % to_string<T>(obj.min) %
to_string<T>(obj.max));
Expand Down Expand Up @@ -84,7 +84,7 @@ PYBIND11_MODULE(pymodel, m) {
bind_limits_class<double>(m, "FloatLimits");
bind_limits_class<geom::Angle>(m, "AngleLimits");
py::class_<model::Model>(m, "Model")
.def(py::init<const std::string &>())
.def(py::init<const std::string&>())
.def_property_readonly("base_max_abs_curvature", &model::Model::baseMaxAbsCurvature)
.def_property_readonly("left_steering_limits", &model::Model::leftSteeringLimits)
.def_property_readonly("right_steering_limits", &model::Model::rightSteeringLimits)
Expand Down
2 changes: 1 addition & 1 deletion packages/model/test/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ TEST(Model, rearToArbitraryPointTwist) {
ASSERT_GEOM_EQUAL(target_twist.velocity, expected_velocity, eps);
}

int main(int argc, char *argv[]) {
int main(int argc, char* argv[]) {
::testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}
2 changes: 1 addition & 1 deletion packages/pure_pursuit/src/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

#include "pure_pursuit/pure_pursuit_node.h"

int main(int argc, char **argv) {
int main(int argc, char** argv) {
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<truck::pure_pursuit::PurePursuitNode>());
rclcpp::shutdown();
Expand Down