Skip to content
This repository has been archived by the owner on Sep 16, 2021. It is now read-only.

replace std_msgs with LaneChangeCommand #72

Merged
merged 1 commit into from
Feb 26, 2021
Merged
Show file tree
Hide file tree
Changes from all 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
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@

#include "autoware_perception_msgs/msg/traffic_light_state_array.hpp"
#include "autoware_planning_msgs/msg/route.hpp"
#include "autoware_planning_msgs/msg/lane_change_command.hpp"
#include "autoware_vehicle_msgs/msg/engage.hpp"
#include "autoware_system_msgs/msg/autoware_state.hpp"
#include "autoware_vehicle_msgs/msg/turn_signal.hpp"
Expand Down Expand Up @@ -188,7 +189,7 @@ class ScenarioAPIAutoware
pub_autoware_engage_; //!< @brief topic pubscriber for autoware engage
rclcpp::Publisher<autoware_debug_msgs::msg::Float32Stamped>::SharedPtr
pub_max_velocity_; //!< @brief topic pubscriber for max velocity
rclcpp::Publisher<std_msgs::msg::Bool>::SharedPtr
rclcpp::Publisher<autoware_planning_msgs::msg::LaneChangeCommand>::SharedPtr
pub_lane_change_permission_; //!< @brief topic pubscriber for approval of lane change
rclcpp::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr
pub_check_point_; //!< @brief topic pubscriber for check point
Expand Down
25 changes: 17 additions & 8 deletions api/scenario_api_autoware/src/scenario_api_autoware.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,9 @@ ScenarioAPIAutoware::ScenarioAPIAutoware(rclcpp::Node::SharedPtr node)

//parameter for getMoveDistance
add_simulator_noise_ = node_->declare_parameter<bool>("rosparam/add_simulator_noise", true);
LOG_SIMPLE(info() << "Parameter 'rosparam/add_simulator_noise' = " << std::boolalpha << add_simulator_noise_);
LOG_SIMPLE(
info() << "Parameter 'rosparam/add_simulator_noise' = " << std::boolalpha <<
add_simulator_noise_);
simulator_noise_pos_dev_ = node_->declare_parameter<double>("rosparam/simulator_pos_noise", 0.1);
LOG_SIMPLE(info() << "Parameter 'rosparam/simulator_pos_noise' = " << simulator_noise_pos_dev_);
autoware_max_velocity_ = node_->declare_parameter<double>("rosparam/max_velocity", 30.0);
Expand All @@ -50,11 +52,15 @@ ScenarioAPIAutoware::ScenarioAPIAutoware(rclcpp::Node::SharedPtr node)
vehicle_data_.wheel_tread = vehicle_info_.wheel_tread_m_;
LOG_SIMPLE(info() << "Parameter '/vehicle_info/wheel_tread' = " << vehicle_data_.wheel_tread);
vehicle_data_.front_overhang = vehicle_info_.front_overhang_m_;
LOG_SIMPLE(info() << "Parameter '/vehicle_info/front_overhang' = " << vehicle_data_.front_overhang);
LOG_SIMPLE(
info() << "Parameter '/vehicle_info/front_overhang' = " <<
vehicle_data_.front_overhang);
vehicle_data_.rear_overhang = vehicle_info_.rear_overhang_m_;
LOG_SIMPLE(info() << "Parameter '/vehicle_info/rear_overhang' = " << vehicle_data_.rear_overhang);
vehicle_data_.vehicle_height = vehicle_info_.vehicle_height_m_;
LOG_SIMPLE(info() << "Parameter '/vehicle_info/vehicle_height' = " << vehicle_data_.vehicle_height);
LOG_SIMPLE(
info() << "Parameter '/vehicle_info/vehicle_height' = " <<
vehicle_data_.vehicle_height);
vehicle_data_.max_longitudinal_offset = vehicle_info_.max_longitudinal_offset_m_;
vehicle_data_.min_longitudinal_offset = vehicle_info_.min_longitudinal_offset_m_;
vehicle_data_.max_height_offset = vehicle_info_.max_height_offset_m_;
Expand Down Expand Up @@ -122,15 +128,18 @@ ScenarioAPIAutoware::ScenarioAPIAutoware(rclcpp::Node::SharedPtr node)
durable_qos);
LOG_SIMPLE(info() << "Advertise topic 'output/initial_velocity'");
pub_autoware_engage_ =
node_->create_publisher<autoware_vehicle_msgs::msg::Engage>("output/autoware_engage", durable_qos);
node_->create_publisher<autoware_vehicle_msgs::msg::Engage>(
"output/autoware_engage",
durable_qos);
LOG_SIMPLE(info() << "Advertise topic 'output/autoware_engage'");
pub_max_velocity_ =
node_->create_publisher<autoware_debug_msgs::msg::Float32Stamped>(
"output/limit_velocity",
durable_qos);
LOG_SIMPLE(info() << "Advertise topic 'output/limit_velocity'");
pub_lane_change_permission_ =
node_->create_publisher<std_msgs::msg::Bool>("output/lane_change_permission", durable_qos);
node_->create_publisher<autoware_planning_msgs::msg::LaneChangeCommand>(
"output/lane_change_permission", durable_qos);
LOG_SIMPLE(info() << "Advertise topic 'output/lane_change_permission'");
pub_check_point_ =
node_->create_publisher<geometry_msgs::msg::PoseStamped>(
Expand Down Expand Up @@ -649,9 +658,9 @@ bool ScenarioAPIAutoware::getRightBlinker() {return getRightBlinker(turn_signal_

bool ScenarioAPIAutoware::approveLaneChange(bool approve_lane_change)
{
std_msgs::msg::Bool boolmsg;
boolmsg.data = approve_lane_change;
pub_lane_change_permission_->publish(boolmsg);
autoware_planning_msgs::msg::LaneChangeCommand lc_cmd;
lc_cmd.command = approve_lane_change;
pub_lane_change_permission_->publish(lc_cmd);
return true; // TODO check successs
}

Expand Down