Skip to content

Commit

Permalink
Merge pull request #44 from iASL-Gifu/feat/param_controller
Browse files Browse the repository at this point in the history
feat: param controller
  • Loading branch information
toki-1441 authored Oct 10, 2024
2 parents d5b25d5 + 50bb972 commit 44bf34b
Show file tree
Hide file tree
Showing 3 changed files with 107 additions and 0 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
cmake_minimum_required(VERSION 3.8)
project(param_controller)

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

# find dependencies
find_package(ament_cmake_auto REQUIRED)

ament_auto_find_build_dependencies()

ament_auto_add_executable(param_controller_node
src/param_controller.cpp
)

ament_auto_package(INSTALL_TO_SHARE
)
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>param_controller</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="yu.asabe@tier4.jp">Yu Asabe</maintainer>
<license>TODO: License declaration</license>

<buildtool_depend>ament_cmake_auto</buildtool_depend>

<depend>rclcpp</depend>
<depend>tier4_vehicle_msgs</depend>
<depend>geometry_msgs</depend>
<depend>sensor_msgs</depend>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>
Original file line number Diff line number Diff line change
@@ -0,0 +1,69 @@
#include <rclcpp/rclcpp.hpp>
#include <tier4_vehicle_msgs/msg/actuation_command_stamped.hpp>

namespace param_controller
{

class ParamController : public rclcpp::Node
{
public:
ParamController()
: Node("param_controller"), steering_value_(0.0)
{
publisher_ = this->create_publisher<tier4_vehicle_msgs::msg::ActuationCommandStamped>(
"/control/command/actuation_cmd", 10);

timer_ = this->create_wall_timer(
std::chrono::milliseconds(50),
std::bind(&ParamController::timer_callback, this));

// Parameter declaration
this->declare_parameter("steering_angle", 0.0);

// Parameter callback
param_callback_handle_ = this->add_on_set_parameters_callback(
std::bind(&ParamController::param_callback, this, std::placeholders::_1));
}

private:
void timer_callback()
{
auto message = tier4_vehicle_msgs::msg::ActuationCommandStamped();
message.header.stamp = this->now();
message.actuation.steer_cmd = steering_value_;
publisher_->publish(message);
RCLCPP_INFO(this->get_logger(), "Publishing: steering_angle = %.2f", steering_value_);
}

rcl_interfaces::msg::SetParametersResult param_callback(
const std::vector<rclcpp::Parameter> & parameters)
{
rcl_interfaces::msg::SetParametersResult result;
result.successful = true;

for (const auto & param : parameters) {
if (param.get_name() == "steering_angle") {
steering_value_ = param.as_double();
RCLCPP_INFO(this->get_logger(), "Parameter updated: steering_angle = %.2f", steering_value_);
}
}

return result;
}

rclcpp::Publisher<tier4_vehicle_msgs::msg::ActuationCommandStamped>::SharedPtr publisher_;
rclcpp::TimerBase::SharedPtr timer_;
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr param_callback_handle_;
double steering_value_;
};

} // namespace param_controller

int main(int argc, char **argv)
{
rclcpp::init(argc, argv);
auto node = std::make_shared<param_controller::ParamController>();
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}

0 comments on commit 44bf34b

Please sign in to comment.