Skip to content

Commit

Permalink
ament_uncrustify --reformat
Browse files Browse the repository at this point in the history
  • Loading branch information
Ar-Ray-code committed Nov 9, 2023
1 parent 216184e commit 4050c4a
Show file tree
Hide file tree
Showing 5 changed files with 201 additions and 213 deletions.
104 changes: 51 additions & 53 deletions joy_rviz_plugin/src/joy_handler.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,68 +27,66 @@

namespace joy_rviz_plugin
{
class JoyHandler
{
public:
JoyHandler(void) {}

void setRosNodePtr(const rclcpp::Node::SharedPtr node_ptr)
{
node_ptr_ = node_ptr;
}
class JoyHandler
{
public:
JoyHandler(void) {}

bool initializePublisher(const std::string topic_name)
{
if (topic_name == "")
{
return false;
}
joy_publisher_ = node_ptr_->create_publisher<sensor_msgs::msg::Joy>(topic_name, rclcpp::QoS(10));
return true;
}
void setRosNodePtr(const rclcpp::Node::SharedPtr node_ptr)
{
node_ptr_ = node_ptr;
}

void finalizePublisher(void)
{
joy_publisher_.reset();
bool initializePublisher(const std::string topic_name)
{
if (topic_name == "") {
return false;
}
joy_publisher_ =
node_ptr_->create_publisher<sensor_msgs::msg::Joy>(topic_name, rclcpp::QoS(10));
return true;
}

void publishJoy(std::vector<float> axes, std::vector<int> buttons)
{
sensor_msgs::msg::Joy msg{};
msg.header.stamp = node_ptr_->now();
msg.axes.resize(2);
msg.axes = axes;
msg.buttons = buttons;
joy_publisher_->publish(msg);
}
void finalizePublisher(void)
{
joy_publisher_.reset();
}

std::vector<std::string> getTwistTopicList(void) const
{
return getTopicList("sensor_msgs/msg/Joy");
}
void publishJoy(std::vector<float> axes, std::vector<int> buttons)
{
sensor_msgs::msg::Joy msg{};
msg.header.stamp = node_ptr_->now();
msg.axes.resize(2);
msg.axes = axes;
msg.buttons = buttons;
joy_publisher_->publish(msg);
}

std::vector<std::string> getTwistTopicList(void) const
{
return getTopicList("sensor_msgs/msg/Joy");
}

private:
std::vector<std::string> getTopicList(const std::string type_name) const
{
std::map<std::string, std::vector<std::string>> topic_map = node_ptr_->get_topic_names_and_types();

std::vector<std::string> output;
for (auto pair : topic_map)
{
for (auto s : pair.second)
{
if (s == type_name)
{
output.push_back(pair.first);
break;
}
private:
std::vector<std::string> getTopicList(const std::string type_name) const
{
std::map<std::string,
std::vector<std::string>> topic_map = node_ptr_->get_topic_names_and_types();

std::vector<std::string> output;
for (auto pair : topic_map) {
for (auto s : pair.second) {
if (s == type_name) {
output.push_back(pair.first);
break;
}
}
return output;
}
return output;
}

rclcpp::Node::SharedPtr node_ptr_;
rclcpp::Publisher<sensor_msgs::msg::Joy>::SharedPtr joy_publisher_;
};
rclcpp::Node::SharedPtr node_ptr_;
rclcpp::Publisher<sensor_msgs::msg::Joy>::SharedPtr joy_publisher_;
};

} // namespace joy_rviz_plugin
243 changes: 118 additions & 125 deletions joy_rviz_plugin/src/joy_panel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,149 +31,142 @@

namespace joy_rviz_plugin
{
JoyPanel::JoyPanel(QWidget *parent) : rviz_common::Panel(parent)
{
QVBoxLayout *layout = new QVBoxLayout;

QHBoxLayout *layout_1st = new QHBoxLayout;
enable_check_ = new QCheckBox("Topic");
layout_1st->addWidget(enable_check_);
topic_combo_ = new QComboBox();
topic_combo_->setEditable(true);
layout_1st->addWidget(topic_combo_);
layout->addLayout(layout_1st);

touch_ = new TouchWidget();
layout->addWidget(touch_);

QHBoxLayout *layout_3rd = new QHBoxLayout;
a_button_ = new QPushButton("A");
b_button_ = new QPushButton("B");
layout_3rd->addWidget(a_button_);
layout_3rd->addWidget(b_button_);
layout->addLayout(layout_3rd);

setLayout(layout);

interval_timer_ = new QTimer(this);

connect(interval_timer_, &QTimer::timeout, this, &JoyPanel::onTick);
connect(enable_check_, &QCheckBox::stateChanged, this, &JoyPanel::onCheckChange);
connect(a_button_, &QPushButton::clicked, this, &JoyPanel::onClickA);
connect(b_button_, &QPushButton::clicked, this, &JoyPanel::onClickB);
connect(touch_, qOverload<QPointF>(&TouchWidget::notifyScaledPoint), this, &JoyPanel::onTouchChange);

interval_timer_->start(100);
touch_->setEnabled(false);
touch_->update();
}
JoyPanel::JoyPanel(QWidget * parent)
: rviz_common::Panel(parent)
{
QVBoxLayout * layout = new QVBoxLayout;

QHBoxLayout * layout_1st = new QHBoxLayout;
enable_check_ = new QCheckBox("Topic");
layout_1st->addWidget(enable_check_);
topic_combo_ = new QComboBox();
topic_combo_->setEditable(true);
layout_1st->addWidget(topic_combo_);
layout->addLayout(layout_1st);

touch_ = new TouchWidget();
layout->addWidget(touch_);

QHBoxLayout * layout_3rd = new QHBoxLayout;
a_button_ = new QPushButton("A");
b_button_ = new QPushButton("B");
layout_3rd->addWidget(a_button_);
layout_3rd->addWidget(b_button_);
layout->addLayout(layout_3rd);

setLayout(layout);

interval_timer_ = new QTimer(this);

connect(interval_timer_, &QTimer::timeout, this, &JoyPanel::onTick);
connect(enable_check_, &QCheckBox::stateChanged, this, &JoyPanel::onCheckChange);
connect(a_button_, &QPushButton::clicked, this, &JoyPanel::onClickA);
connect(b_button_, &QPushButton::clicked, this, &JoyPanel::onClickB);
connect(
touch_, qOverload<QPointF>(
&TouchWidget::notifyScaledPoint), this, &JoyPanel::onTouchChange);

interval_timer_->start(100);
touch_->setEnabled(false);
touch_->update();
}

void JoyPanel::onInitialize()
{
joy_handler_.setRosNodePtr(
this->getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node());
updateTopicList();
}

void JoyPanel::onInitialize()
{
joy_handler_.setRosNodePtr(this->getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node());
void JoyPanel::onCheckChange(int state)
{
if (state == Qt::Checked) {
std::string topic_name = topic_combo_->currentText().toStdString();
bool ret = joy_handler_.initializePublisher(topic_name);
if (!ret) {
return;
}
topic_combo_->setEnabled(false);
touch_->setEnabled(true);
is_active_ = true;
} else {
joy_handler_.finalizePublisher();
topic_combo_->setEnabled(true);
touch_->setEnabled(false);
is_active_ = false;
updateTopicList();
}
}

void JoyPanel::onCheckChange(int state)
{
if (state == Qt::Checked)
{
std::string topic_name = topic_combo_->currentText().toStdString();
bool ret = joy_handler_.initializePublisher(topic_name);
if (!ret)
{
return;
}
topic_combo_->setEnabled(false);
touch_->setEnabled(true);
is_active_ = true;
}
else
{
joy_handler_.finalizePublisher();
topic_combo_->setEnabled(true);
touch_->setEnabled(false);
is_active_ = false;
updateTopicList();
}
}
void JoyPanel::onClickA()
{
a_clicked_ = true;
}

void JoyPanel::onClickA()
{
a_clicked_ = true;
}
void JoyPanel::onClickB()
{
b_clicked_ = true;
}

void JoyPanel::onClickB()
{
b_clicked_ = true;
void JoyPanel::onTick()
{
if (is_active_) {
float axis0 = -touch_point_.y();
float axis1 = -touch_point_.x();
joy_handler_.publishJoy({axis0, axis1}, {a_clicked_, b_clicked_});
a_clicked_ = false;
b_clicked_ = false;
}
}

void JoyPanel::onTick()
{
if (is_active_)
{
float axis0 = -touch_point_.y();
float axis1 = -touch_point_.x();
joy_handler_.publishJoy({axis0, axis1}, {a_clicked_, b_clicked_});
a_clicked_ = false;
b_clicked_ = false;
}
}
void JoyPanel::save(rviz_common::Config config) const
{
rviz_common::Panel::save(config);
config.mapSetValue("BaseTopic", topic_combo_->currentText());
config.mapSetValue("Checked", enable_check_->isChecked());
}

void JoyPanel::save(rviz_common::Config config) const
{
rviz_common::Panel::save(config);
config.mapSetValue("BaseTopic", topic_combo_->currentText());
config.mapSetValue("Checked", enable_check_->isChecked());
void JoyPanel::load(const rviz_common::Config & config)
{
rviz_common::Panel::load(config);
QString tmp_text;
bool tmp_bool;
if (config.mapGetString("BaseTopic", &tmp_text)) {
topic_combo_->setCurrentText(tmp_text);
}

void JoyPanel::load(const rviz_common::Config &config)
{
rviz_common::Panel::load(config);
QString tmp_text;
bool tmp_bool;
if (config.mapGetString("BaseTopic", &tmp_text))
{
topic_combo_->setCurrentText(tmp_text);
}
if (config.mapGetBool("Checked", &tmp_bool))
{
enable_check_->setChecked(tmp_bool);
}
if (config.mapGetBool("Checked", &tmp_bool)) {
enable_check_->setChecked(tmp_bool);
}
}

void JoyPanel::updateTopicList(void)
{
std::string previous_topic_name = topic_combo_->currentText().toStdString();
auto topic_list = joy_handler_.getTwistTopicList();
topic_combo_->clear();
int same_topic_index = -1;
for (auto t : topic_list)
{
topic_combo_->addItem(t.c_str());
if (t == previous_topic_name)
{
same_topic_index = topic_combo_->count() - 1;
}
void JoyPanel::updateTopicList(void)
{
std::string previous_topic_name = topic_combo_->currentText().toStdString();
auto topic_list = joy_handler_.getTwistTopicList();
topic_combo_->clear();
int same_topic_index = -1;
for (auto t : topic_list) {
topic_combo_->addItem(t.c_str());
if (t == previous_topic_name) {
same_topic_index = topic_combo_->count() - 1;
}
}

if (previous_topic_name != "")
{
if (same_topic_index < 0)
{
topic_combo_->addItem(previous_topic_name.c_str());
same_topic_index = topic_combo_->count() - 1;
}
topic_combo_->setCurrentIndex(same_topic_index);
if (previous_topic_name != "") {
if (same_topic_index < 0) {
topic_combo_->addItem(previous_topic_name.c_str());
same_topic_index = topic_combo_->count() - 1;
}
topic_combo_->setCurrentIndex(same_topic_index);
}
}

void JoyPanel::onTouchChange(QPointF point)
{
touch_point_ = point;
}
void JoyPanel::onTouchChange(QPointF point)
{
touch_point_ = point;
}

} // namespace joy_rviz_plugin

#include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(joy_rviz_plugin::JoyPanel, rviz_common::Panel)
PLUGINLIB_EXPORT_CLASS(joy_rviz_plugin::JoyPanel, rviz_common::Panel)
Loading

0 comments on commit 4050c4a

Please sign in to comment.