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

feat(raw_vehicle_cmd_converter): use polling subscriber #7319

Merged
Show file tree
Hide file tree
Changes from 2 commits
Commits
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
12 changes: 6 additions & 6 deletions vehicle/raw_vehicle_cmd_converter/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -22,15 +22,15 @@ Once the acceleration map is crafted, it should be loaded when the RawVehicleCmd

### Auto-Calibration Tool

For ease of calibration and adjustments to the lookup table, an auto-calibration tool is available. More information and instructions for this tool can be found [here](https://github.com/autowarefoundation/autoware.universe/blob/main/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/README.md).
For ease of calibration and adjustments to the lookup table, an auto-calibration tool is available. More information and instructions for this tool can be found [here](https://github.com/autowarefoundation/autoware.universe/blob/main/vehicle/accel_brake_map_calibrator/README.md).

## Input topics

| Name | Type | Description |
| --------------------- | ------------------------------------- | ------------------------------------------------------------------------------------------------------------------ |
| `~/input/control_cmd` | autoware_control_msgs::msg::Control | target `velocity/acceleration/steering_angle/steering_angle_velocity` is necessary to calculate actuation command. |
| `~/input/steering"` | autoware_vehicle_msgs::SteeringReport | current status of steering used for steering feed back control |
| `~/input/twist` | navigation_msgs::Odometry | twist topic in odometry is used. |
| Name | Type | Description |
| --------------------- | ------------------------------------------ | ------------------------------------------------------------------------------------------------------------------ |
| `~/input/control_cmd` | autoware_control_msgs::msg::Control | target `velocity/acceleration/steering_angle/steering_angle_velocity` is necessary to calculate actuation command. |
| `~/input/steering"` | autoware_vehicle_msgs::msg::SteeringReport | current status of steering used for steering feed back control |
| `~/input/odometry` | navigation_msgs::Odometry | twist topic in odometry is used. |

## Output topics

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include "raw_vehicle_cmd_converter/pid.hpp"
#include "raw_vehicle_cmd_converter/steer_map.hpp"
#include "tier4_autoware_utils/ros/logger_level_configure.hpp"
#include "tier4_autoware_utils/ros/polling_subscriber.hpp"

#include <rclcpp/rclcpp.hpp>

Expand Down Expand Up @@ -74,12 +75,13 @@ class RawVehicleCommandConverterNode : public rclcpp::Node

//!< @brief topic publisher for low level vehicle command
rclcpp::Publisher<ActuationCommandStamped>::SharedPtr pub_actuation_cmd_;
//!< @brief subscriber for current velocity
rclcpp::Subscription<Odometry>::SharedPtr sub_velocity_;
//!< @brief subscriber for vehicle command
rclcpp::Subscription<Control>::SharedPtr sub_control_cmd_;
//!< @brief subscriber for steering
rclcpp::Subscription<Steering>::SharedPtr sub_steering_;
// polling subscribers
tier4_autoware_utils::InterProcessPollingSubscriber<Odometry> sub_odometry_{
this, "~/input/odometry"};
tier4_autoware_utils::InterProcessPollingSubscriber<Steering> sub_steering_{
this, "~/input/steering"};

rclcpp::TimerBase::SharedPtr timer_;

Expand Down Expand Up @@ -109,9 +111,9 @@ class RawVehicleCommandConverterNode : public rclcpp::Node
const double current_velocity, const double desired_acc, bool & accel_cmd_is_zero);
double calculateBrakeMap(const double current_velocity, const double desired_acc);
double calculateSteer(const double vel, const double steering, const double steer_rate);
void onSteering(const Steering::ConstSharedPtr msg);
void processSteering(const Steering::ConstSharedPtr msg);
void onControlCmd(const Control::ConstSharedPtr msg);
void onVelocity(const Odometry::ConstSharedPtr msg);
void processOdometry(const Odometry::ConstSharedPtr msg);
void publishActuationCmd();
// for debugging
rclcpp::Publisher<Float32MultiArrayStamped>::SharedPtr debug_pub_steer_pid_;
Expand Down
18 changes: 12 additions & 6 deletions vehicle/raw_vehicle_cmd_converter/src/node.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2021 Tier IV, Inc. All rights reserved.

Check notice on line 1 in vehicle/raw_vehicle_cmd_converter/src/node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Overall Code Complexity

The mean cyclomatic complexity increases from 4.25 to 4.50, threshold = 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -78,10 +78,6 @@
pub_actuation_cmd_ = create_publisher<ActuationCommandStamped>("~/output/actuation_cmd", 1);
sub_control_cmd_ = create_subscription<Control>(
"~/input/control_cmd", 1, std::bind(&RawVehicleCommandConverterNode::onControlCmd, this, _1));
sub_velocity_ = create_subscription<Odometry>(
"~/input/odometry", 1, std::bind(&RawVehicleCommandConverterNode::onVelocity, this, _1));
sub_steering_ = create_subscription<Steering>(
"~/input/steering", 1, std::bind(&RawVehicleCommandConverterNode::onSteering, this, _1));
debug_pub_steer_pid_ = create_publisher<Float32MultiArrayStamped>(
"/vehicle/raw_vehicle_cmd_converter/debug/steer_pid", 1);

Expand Down Expand Up @@ -204,20 +200,30 @@
return desired_brake_cmd;
}

void RawVehicleCommandConverterNode::onSteering(const Steering::ConstSharedPtr msg)
void RawVehicleCommandConverterNode::processSteering(const Steering::ConstSharedPtr msg)
{
if (!msg) {
return;
}
current_steer_ptr_ = std::make_unique<double>(msg->steering_tire_angle);
}

void RawVehicleCommandConverterNode::onVelocity(const Odometry::ConstSharedPtr msg)
void RawVehicleCommandConverterNode::processOdometry(const Odometry::ConstSharedPtr msg)
{
if (!msg) {
return;
}
current_twist_ptr_ = std::make_unique<TwistStamped>();
current_twist_ptr_->header = msg->header;
current_twist_ptr_->twist = msg->twist.twist;
}

void RawVehicleCommandConverterNode::onControlCmd(const Control::ConstSharedPtr msg)
{
const auto odometry_msg = sub_odometry_.takeData();
const auto steering_msg = sub_steering_.takeData();
processOdometry(odometry_msg);
processSteering(steering_msg);
control_cmd_ptr_ = msg;
publishActuationCmd();
}
Expand Down
Loading