Skip to content

Commit

Permalink
Adapt CarlaControlPanel
Browse files Browse the repository at this point in the history
  • Loading branch information
berndgassmann committed Jul 23, 2024
1 parent c821621 commit 55544e4
Show file tree
Hide file tree
Showing 3 changed files with 8 additions and 16 deletions.
19 changes: 7 additions & 12 deletions rviz_carla_plugin/src/carla_control_panel_ROS2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -175,12 +175,10 @@ void CarlaControlPanel::onInitialize()
_node = getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node();

// set up ros subscriber and publishers
mCarlaStatusSubscriber = _node->create_subscription<carla_msgs::msg::CarlaStatus>("/carla/world/status", rclcpp::SensorDataQoS().keep_last(10), std::bind(&CarlaControlPanel::carlaStatusChanged, this, _1));
mCarlaStatusSubscriber = _node->create_subscription<carla_msgs::msg::CarlaStatus>("/carla/world/status", rclcpp::SensorDataQoS().keep_last(10).transient_local(), std::bind(&CarlaControlPanel::carlaStatusChanged, this, _1));
mCarlaControlPublisher = _node->create_publisher<carla_msgs::msg::CarlaControl>("/carla/world/control", 10);
mVehicleStatusSubscriber
= _node->create_subscription<carla_msgs::msg::CarlaVehicleStatus>("/carla/vehicles/hero/vehicle_status", 1000, std::bind(&CarlaControlPanel::vehicleStatusChanged, this, _1));
mVehicleOdometrySubscriber
= _node->create_subscription<nav_msgs::msg::Odometry>("/carla/vehicles/hero/odometry", 1000, std::bind(&CarlaControlPanel::vehicleOdometryChanged, this, _1));

auto qos_latch_10 = rclcpp::QoS( rclcpp::QoSInitialization(RMW_QOS_POLICY_HISTORY_KEEP_LAST, 10));
qos_latch_10.durability(RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL);
Expand Down Expand Up @@ -313,16 +311,13 @@ void CarlaControlPanel::vehicleStatusChanged(const carla_msgs::msg::CarlaVehicle
std::stringstream speedStream;
speedStream << std::fixed << std::setprecision(2) << msg->velocity * 3.6;
mSpeedLabel->setText(speedStream.str().c_str());
}

void CarlaControlPanel::vehicleOdometryChanged(const nav_msgs::msg::Odometry::SharedPtr msg)
{
std::stringstream posStream;
posStream << std::fixed << std::setprecision(2) << msg->pose.pose.position.x << ", " << msg->pose.pose.position.y;
posStream << std::fixed << std::setprecision(2) << msg->pose.position.x << ", " << msg->pose.position.y;
mPosLabel->setText(posStream.str().c_str());

std::stringstream headingStream;
headingStream << std::fixed << std::setprecision(2) << tf2::getYaw(msg->pose.pose.orientation);
headingStream << std::fixed << std::setprecision(2) << tf2::getYaw(msg->pose.orientation);
mHeadingLabel->setText(headingStream.str().c_str());
}

Expand All @@ -347,11 +342,11 @@ void CarlaControlPanel::setSimulationButtonStatus(bool active)
void CarlaControlPanel::carlaStatusChanged(const carla_msgs::msg::CarlaStatus::SharedPtr msg)
{
mCarlaStatus = msg;
setSimulationButtonStatus(mCarlaStatus->synchronous_mode);
setSimulationButtonStatus(mCarlaStatus->episode_settings.synchronous_mode);

if (mCarlaStatus->synchronous_mode)
if (mCarlaStatus->episode_settings.synchronous_mode)
{
if (mCarlaStatus->synchronous_mode_running)
if (mCarlaStatus->game_running)
{
QPixmap pixmap(":/icons/pause.png");
QIcon iconPause(pixmap);
Expand All @@ -378,7 +373,7 @@ void CarlaControlPanel::carlaTogglePlayPause()
if (mCarlaStatus)
{
carla_msgs::msg::CarlaControl ctrl;
if (mCarlaStatus->synchronous_mode_running)
if (mCarlaStatus->game_running)
{
ctrl.command = carla_msgs::msg::CarlaControl::PAUSE;
}
Expand Down
3 changes: 0 additions & 3 deletions rviz_carla_plugin/src/carla_control_panel_ROS2.h
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,6 @@
#include <carla_msgs/msg/carla_control.hpp>
#include <carla_ros_scenario_runner_types/msg/carla_scenario_list.hpp>
#include <carla_ros_scenario_runner_types/msg/carla_scenario_runner_status.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include "rclcpp/rclcpp.hpp"
#include <rviz_common/panel.hpp>
#include <std_msgs/msg/bool.hpp>
Expand Down Expand Up @@ -68,7 +67,6 @@ protected Q_SLOTS:
void scenarioRunnerStatusChanged(const carla_ros_scenario_runner_types::msg::CarlaScenarioRunnerStatus::SharedPtr msg);
void carlaStatusChanged(const carla_msgs::msg::CarlaStatus::SharedPtr msg);
void vehicleStatusChanged(const carla_msgs::msg::CarlaVehicleStatus::SharedPtr msg);
void vehicleOdometryChanged(const nav_msgs::msg::Odometry::SharedPtr msg);
void carlaScenariosChanged(const carla_ros_scenario_runner_types::msg::CarlaScenarioList::SharedPtr msg);
carla_msgs::msg::CarlaStatus::SharedPtr mCarlaStatus{nullptr};

Expand All @@ -92,7 +90,6 @@ protected Q_SLOTS:
rclcpp::Publisher<std_msgs::msg::Bool>::SharedPtr mVehicleControlManualOverridePublisher;
rclcpp::Subscription<carla_msgs::msg::CarlaStatus>::SharedPtr mCarlaStatusSubscriber;
rclcpp::Subscription<carla_msgs::msg::CarlaVehicleStatus>::SharedPtr mVehicleStatusSubscriber;
rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr mVehicleOdometrySubscriber;
rclcpp::Client<carla_ros_scenario_runner_types::srv::ExecuteScenario>::SharedPtr mExecuteScenarioClient;
rclcpp::Subscription<carla_ros_scenario_runner_types::msg::CarlaScenarioList>::SharedPtr mScenarioSubscriber;
rclcpp::Subscription<carla_ros_scenario_runner_types::msg::CarlaScenarioRunnerStatus>::SharedPtr mScenarioRunnerStatusSubscriber;
Expand Down

0 comments on commit 55544e4

Please sign in to comment.