Skip to content

Commit

Permalink
ci: add pre-commit action (#42)
Browse files Browse the repository at this point in the history
Signed-off-by: Takagi, Isamu <[email protected]>
  • Loading branch information
isamu-takagi authored Jun 18, 2024
1 parent 30104f1 commit 060e3e8
Show file tree
Hide file tree
Showing 38 changed files with 598 additions and 351 deletions.
2 changes: 1 addition & 1 deletion .clang-format
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ BraceWrapping:
AfterStruct: true
BeforeLambdaBody: true
BreakBeforeBraces: Custom
ColumnLimit: 150
ColumnLimit: 120
ConstructorInitializerIndentWidth: 0
ContinuationIndentWidth: 2
DerivePointerAlignment: false
Expand Down
14 changes: 14 additions & 0 deletions .github/workflows/pre-commit.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
name: pre-commit

on:
pull_request:
push:
branches: [main]

jobs:
pre-commit:
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v3
- uses: actions/setup-python@v3
- uses: pre-commit/[email protected]
2 changes: 1 addition & 1 deletion CPPLINT.cfg
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
# Modified from https://github.com/ament/ament_lint/blob/ebd524bb9973d5ec1dc48a670ce54f958a5a0243/ament_cpplint/ament_cpplint/main.py#L64-L120
set noparent
linelength=150
linelength=120
includeorder=standardcfirst
filter=-build/c++17 # we do allow C++17
filter=-build/namespaces_literals # we allow using namespace for literals
Expand Down
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
@@ -1 +1 @@
# autoware-practice
# autoware-practice
2 changes: 1 addition & 1 deletion setup.cfg
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
[flake8]
extend-ignore = D100,D101,D102,D103,D104,D105,D106,D107,Q000,CNL100
extend-ignore = D100,D101,D102,D103,D104,D105,D106,D107,E231,Q000,CNL100
import-order-style = pep8
max-line-length = 150
show-source = true
Expand Down
2 changes: 1 addition & 1 deletion src/autoware_practice_course/config/trajectory.csv
Original file line number Diff line number Diff line change
Expand Up @@ -98,4 +98,4 @@ position_x, position_y, longitudinal_velocity_mps
97.0,0.0,0.6
98.0,0.0,0.4
99.0,0.0,0.2
100.0,0.0,0.0
100.0,0.0,0.0
2 changes: 1 addition & 1 deletion src/autoware_practice_course/config/trajectory_zigzag.csv
Original file line number Diff line number Diff line change
Expand Up @@ -98,4 +98,4 @@ position_x, position_y, longitudinal_velocity_mps
57.0,40.0,0.6
58.0,40.0,0.4
59.0,40.0,0.2
60.0,40.0,0.0
60.0,40.0,0.0
2 changes: 1 addition & 1 deletion src/autoware_practice_course/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,8 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>

<depend>autoware_auto_control_msgs</depend>
<depend>autoware_auto_vehicle_msgs</depend>
<depend>autoware_auto_planning_msgs</depend>
<depend>autoware_auto_vehicle_msgs</depend>
<depend>geometry_msgs</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
Expand Down
3 changes: 2 additions & 1 deletion src/autoware_practice_course/src/vehicle/backward.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,8 @@ SampleNode::SampleNode() : Node("backward")
using std::placeholders::_1;
pub_command_ = create_publisher<AckermannControlCommand>("/control/command/control_cmd", rclcpp::QoS(1));
pub_gear_ = create_publisher<GearCommand>("/control/command/gear_cmd", rclcpp::QoS(1));
sub_gear_ = create_subscription<GearReport>("/vehicle/status/gear_status", rclcpp::QoS(1), std::bind(&SampleNode::on_gear, this, _1));
sub_gear_ = create_subscription<GearReport>(
"/vehicle/status/gear_status", rclcpp::QoS(1), std::bind(&SampleNode::on_gear, this, _1));

const auto period = rclcpp::Rate(10).period();
timer_ = rclcpp::create_timer(this, get_clock(), period, [this] { on_timer(); });
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,20 @@
// Copyright 2024 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under #include <memory>the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include "longitudinal_controller.hpp"

#include <limits>
#include <memory>

namespace autoware_practice_course
Expand All @@ -12,8 +27,10 @@ SampleNode::SampleNode() : Node("longitudinal_controller"), kp_(0.0)
get_parameter("kp", kp_);

pub_command_ = create_publisher<AckermannControlCommand>("/control/command/control_cmd", rclcpp::QoS(1));
sub_trajectory_ = create_subscription<Trajectory>("/planning/scenario_planning/trajectory", rclcpp::QoS(1), std::bind(&SampleNode::update_target_velocity, this, _1));
sub_kinematic_state_= create_subscription<Odometry>("/localization/kinematic_state", rclcpp::QoS(1), std::bind(&SampleNode::update_current_state, this, _1));
sub_trajectory_ = create_subscription<Trajectory>(
"/planning/scenario_planning/trajectory", rclcpp::QoS(1), std::bind(&SampleNode::update_target_velocity, this, _1));
sub_kinematic_state_ = create_subscription<Odometry>(
"/localization/kinematic_state", rclcpp::QoS(1), std::bind(&SampleNode::update_current_state, this, _1));

const auto period = rclcpp::Rate(10).period();
timer_ = rclcpp::create_timer(this, get_clock(), period, [this] { on_timer(); });
Expand Down Expand Up @@ -51,17 +68,18 @@ void SampleNode::on_timer()

AckermannControlCommand command;
command.stamp = stamp;

double velocity_error = target_velocity_ - current_velocity_;
command.longitudinal.acceleration = kp_ * velocity_error;
command.longitudinal.speed = target_velocity_; // メッセージ型としてはspeedがあるが、vehiclle interface側では加速度しか受け取っていない。

command.longitudinal.speed = target_velocity_; // メッセージ型としてはspeedがあるが、vehiclle
// interface側では加速度しか受け取っていない。

command.lateral.steering_tire_angle = 0.0;

pub_command_->publish(command);
}

}
} // namespace autoware_practice_course

int main(int argc, char ** argv)
{
Expand All @@ -70,4 +88,4 @@ int main(int argc, char ** argv)
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}
}
Original file line number Diff line number Diff line change
@@ -1,11 +1,25 @@
#ifndef TRAJECTORY_PLANNER_HPP_
#define TRAJECTORY_PLANNER_HPP_
// Copyright 2024 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under #include <memory>the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef VELOCITY_PLANNING__LONGITUDINAL_CONTROLLER_HPP_
#define VELOCITY_PLANNING__LONGITUDINAL_CONTROLLER_HPP_

#include <rclcpp/rclcpp.hpp>
#include <autoware_auto_planning_msgs/msg/trajectory.hpp>
#include <autoware_auto_control_msgs/msg/ackermann_control_command.hpp>
#include <autoware_auto_planning_msgs/msg/trajectory.hpp>
#include <geometry_msgs/msg/point.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <geometry_msgs/msg/point.hpp>
namespace autoware_practice_course
{

Expand Down Expand Up @@ -33,6 +47,6 @@ class SampleNode : public rclcpp::Node
double kp_;
};

}
} // namespace autoware_practice_course

#endif
#endif // VELOCITY_PLANNING__LONGITUDINAL_CONTROLLER_HPP_
Original file line number Diff line number Diff line change
@@ -1,3 +1,17 @@
// Copyright 2024 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under #include <memory>the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include "p_controller.hpp"

#include <memory>
Expand All @@ -14,11 +28,10 @@ SampleNode::SampleNode() : Node("p_controller")
get_parameter("target_velocity", target_velocity_);

pub_command_ = create_publisher<AckermannControlCommand>("/control/command/control_cmd", rclcpp::QoS(1));

velocity_subscriber_ = create_subscription<VelocityReport>(
"/vehicle/status/velocity_status", 10, [this](const VelocityReport::SharedPtr msg) {
current_velocity_ = msg->longitudinal_velocity;
});
"/vehicle/status/velocity_status", 10,
[this](const VelocityReport::SharedPtr msg) { current_velocity_ = msg->longitudinal_velocity; });

const auto period = rclcpp::Rate(10).period();
timer_ = rclcpp::create_timer(this, get_clock(), period, [this] { on_timer(); });
Expand All @@ -30,17 +43,17 @@ void SampleNode::on_timer()

AckermannControlCommand command;
command.stamp = stamp;

double velocity_error = target_velocity_ - current_velocity_;
command.longitudinal.acceleration = kp_ * velocity_error;
command.longitudinal.speed = target_velocity_;

command.lateral.steering_tire_angle = 0.0;

pub_command_->publish(command);
}

}
} // namespace autoware_practice_course

int main(int argc, char ** argv)
{
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,19 @@
#ifndef P_CONTROLLER_HPP_
#define P_CONTROLLER_HPP_
// Copyright 2024 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under #include <memory>the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef VELOCITY_PLANNING__P_CONTROLLER_HPP_
#define VELOCITY_PLANNING__P_CONTROLLER_HPP_

#include <rclcpp/rclcpp.hpp>
#include <autoware_auto_control_msgs/msg/ackermann_control_command.hpp>
Expand Down Expand Up @@ -34,6 +48,6 @@ class SampleNode : public rclcpp::Node
void velocity_callback(const VelocityReport::SharedPtr msg);
};

}
} // namespace autoware_practice_course

#endif
#endif // VELOCITY_PLANNING__P_CONTROLLER_HPP_
Original file line number Diff line number Diff line change
@@ -1,5 +1,21 @@
// Copyright 2024 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under #include <memory>the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include "trajectory_follower.hpp"

#include <fstream>
#include <limits>

namespace autoware_practice_course
{
Expand All @@ -17,8 +33,10 @@ SampleNode::SampleNode() : Node("trajectory_follower"), kp_(0.0), lookahead_dist
RCLCPP_INFO(this->get_logger(), "Wheel base: %f", wheel_base_);

pub_command_ = create_publisher<AckermannControlCommand>("/control/command/control_cmd", rclcpp::QoS(1));
sub_trajectory_ = create_subscription<Trajectory>("/planning/scenario_planning/trajectory", rclcpp::QoS(1), std::bind(&SampleNode::update_target_velocity, this, _1));
sub_kinematic_state_= create_subscription<Odometry>("/localization/kinematic_state", rclcpp::QoS(1), std::bind(&SampleNode::update_current_state, this, _1));
sub_trajectory_ = create_subscription<Trajectory>(
"/planning/scenario_planning/trajectory", rclcpp::QoS(1), std::bind(&SampleNode::update_target_velocity, this, _1));
sub_kinematic_state_ = create_subscription<Odometry>(
"/localization/kinematic_state", rclcpp::QoS(1), std::bind(&SampleNode::update_current_state, this, _1));

const auto period = rclcpp::Rate(10).period();
timer_ = rclcpp::create_timer(this, get_clock(), period, [this] { on_timer(); });
Expand All @@ -27,7 +45,6 @@ SampleNode::SampleNode() : Node("trajectory_follower"), kp_(0.0), lookahead_dist
void SampleNode::update_target_velocity(const Trajectory & msg)
{
double min_distance = std::numeric_limits<double>::max();


for (size_t i = 0; i < msg.points.size(); ++i) {
double dx = msg.points[i].pose.position.x - current_position_.x;
Expand Down Expand Up @@ -68,7 +85,6 @@ double SampleNode::load_parameters(const std::string & param_file, const std::st
return -1.0;
}


void SampleNode::update_current_state(const Odometry & msg)
{
current_velocity_ = msg.twist.twist.linear.x;
Expand All @@ -82,13 +98,13 @@ void SampleNode::on_timer()

AckermannControlCommand command;
command.stamp = stamp;

double velocity_error = target_velocity_ - current_velocity_;
command.longitudinal.acceleration = longitudinal_controller(velocity_error);
command.longitudinal.speed = target_velocity_;

command.lateral.steering_tire_angle = lateral_controller();

pub_command_->publish(command);
}

Expand Down Expand Up @@ -125,16 +141,17 @@ double SampleNode::lateral_controller()
return steering_angle;
}

double SampleNode::calculate_yaw_from_quaternion(const geometry_msgs::msg::Quaternion& q) {
// Convert quaternion to Euler angles
double siny_cosp = 2 * (q.w * q.z + q.x * q.y);
double cosy_cosp = 1 - 2 * (q.y * q.y + q.z * q.z);
double yaw = std::atan2(siny_cosp, cosy_cosp);
double SampleNode::calculate_yaw_from_quaternion(const geometry_msgs::msg::Quaternion & q)
{
// Convert quaternion to Euler angles
double siny_cosp = 2 * (q.w * q.z + q.x * q.y);
double cosy_cosp = 1 - 2 * (q.y * q.y + q.z * q.z);
double yaw = std::atan2(siny_cosp, cosy_cosp);

return yaw;
return yaw;
}

}
} // namespace autoware_practice_course

int main(int argc, char ** argv)
{
Expand All @@ -143,4 +160,4 @@ int main(int argc, char ** argv)
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}
}
Loading

0 comments on commit 060e3e8

Please sign in to comment.