Skip to content
Snippets Groups Projects
Commit 535aba09 authored by bpwilcox's avatar bpwilcox
Browse files

lint and uncrustify cleanup

parent 1f28d27a
No related branches found
No related tags found
No related merge requests found
......@@ -51,7 +51,7 @@ protected:
const std::shared_ptr<ManageLifecycleNodes::Request> request,
std::shared_ptr<ManageLifecycleNodes::Response> response);
void activeCallback(
void isActiveCallback(
const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<std_srvs::srv::Trigger::Request> request,
std::shared_ptr<std_srvs::srv::Trigger::Response> response);
......
......@@ -52,7 +52,7 @@ LifecycleManager::LifecycleManager()
std::bind(&LifecycleManager::managerCallback, this, _1, _2, _3));
is_active_srv_ = create_service<std_srvs::srv::Trigger>("lifecycle_manager/is_active",
std::bind(&LifecycleManager::activeCallback, this, _1, _2, _3));
std::bind(&LifecycleManager::isActiveCallback, this, _1, _2, _3));
auto options = rclcpp::NodeOptions().arguments(
{"--ros-args", "-r", std::string("__node:=") + get_name() + "service_client", "--"});
......@@ -110,9 +110,9 @@ LifecycleManager::managerCallback(
}
void
LifecycleManager::activeCallback(
LifecycleManager::isActiveCallback(
const std::shared_ptr<rmw_request_id_t>/*request_header*/,
const std::shared_ptr<std_srvs::srv::Trigger::Request> /*request*/,
const std::shared_ptr<std_srvs::srv::Trigger::Request>/*request*/,
std::shared_ptr<std_srvs::srv::Trigger::Response> response)
{
response->success = system_active_;
......
......@@ -78,8 +78,6 @@ private:
nav2_msgs::action::NavigateToPose::Goal goal_;
GoalHandle::SharedPtr goal_handle_;
// A timer used to check on the completion status of the action
// The client used to control the nav2 stack
nav2_lifecycle_manager::LifecycleManagerClient client_;
......@@ -104,12 +102,14 @@ private:
class InitialThread : public QThread
{
Q_OBJECT
public:
InitialThread(nav2_lifecycle_manager::LifecycleManagerClient & client)
explicit InitialThread(nav2_lifecycle_manager::LifecycleManagerClient & client)
: client_(client)
{}
void run() override {
void run() override
{
auto response = client_.is_active();
if (response) {
emit activeSystem();
......@@ -126,7 +126,6 @@ private:
nav2_lifecycle_manager::LifecycleManagerClient client_;
};
} // namespace nav2_rviz_plugins
#endif // NAV2_RVIZ_PLUGINS__NAV2_PANEL_HPP_
......@@ -96,11 +96,13 @@ Nav2Panel::Nav2Panel(QWidget * parent)
InitialThread * initialThread = new InitialThread(client_);
connect(initialThread, &InitialThread::finished, initialThread, &QObject::deleteLater);
QSignalTransition * activeSignal = new QSignalTransition(initialThread, &InitialThread::activeSystem);
QSignalTransition * activeSignal = new QSignalTransition(initialThread,
&InitialThread::activeSystem);
activeSignal->setTargetState(idle_);
pre_initial_->addTransition(activeSignal);
QSignalTransition * inactiveSignal = new QSignalTransition(initialThread, &InitialThread::inactiveSystem);
QSignalTransition * inactiveSignal = new QSignalTransition(initialThread,
&InitialThread::inactiveSystem);
inactiveSignal->setTargetState(initial_);
pre_initial_->addTransition(inactiveSignal);
......
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment