Skip to content

Commit

Permalink
Ros2 devel (#8)
Browse files Browse the repository at this point in the history
More work on basic command chain class hierarchy.
  • Loading branch information
Michael Jeronimo authored Jul 25, 2018
1 parent 699debf commit 69a647c
Show file tree
Hide file tree
Showing 15 changed files with 205 additions and 29 deletions.
3 changes: 3 additions & 0 deletions src/task/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,9 @@ add_library(task STATIC
src/NavigationTask.cpp
src/PlanningTask.cpp
src/RobotTask.cpp
src/Task.cpp
src/AStarPlanner.cpp
src/DwaController.cpp
)

ament_target_dependencies(task
Expand Down
23 changes: 23 additions & 0 deletions src/task/include/task/AStarPlanner.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
// License: Apache 2.0. See LICENSE file in root directory.
// Copyright 2018 Intel Corporation. All Rights Reserved.

#ifndef TASK__ASTARPLANNER_HPP_
#define TASK__ASTARPLANNER_HPP_

#include "task/PlanningTask.hpp"

class AStarPlanner : public PlanningTask
{
public:
AStarPlanner(const std::string & name);
AStarPlanner() = delete;
~AStarPlanner();

void createPlan(const geometry_msgs::msg::PoseStamped & start,
const geometry_msgs::msg::PoseStamped & goal);

protected:
void workerThread() override;
};

#endif // TASK__ASTARPLANNER_HPP_
4 changes: 2 additions & 2 deletions src/task/include/task/ControlTask.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,11 +9,11 @@
class ControlTask : public RobotTask
{
public:
explicit ControlTask(Robot * robot);
explicit ControlTask(const std::string & name, Robot * robot);
ControlTask() = delete;
~ControlTask();

// executePlan()
virtual void executePlan() = 0;
};

#endif // TASK__CONTROLTASK_HPP_
22 changes: 22 additions & 0 deletions src/task/include/task/DwaController.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
// License: Apache 2.0. See LICENSE file in root directory.
// Copyright 2018 Intel Corporation. All Rights Reserved.

#ifndef TASK__SPECIFICCONTROLLER_HPP_
#define TASK__SPECIFICCONTROLLER_HPP_

#include "task/ControlTask.hpp"

class DwaController : public ControlTask
{
public:
DwaController(const std::string & name, Robot * robot);
DwaController() = delete;
~DwaController();

void executePlan() override;

protected:
void workerThread() override;
};

#endif // TASK__SPECIFICCONTROLLER_HPP_
10 changes: 5 additions & 5 deletions src/task/include/task/NavigationTask.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,19 +5,19 @@
#define TASK__NAVIGATIONTASK_HPP_

#include "task/RobotTask.hpp"
#include "task/PlanningTask.hpp"
#include "task/ControlTask.hpp"
#include "task/AStarPlanner.hpp"
#include "task/DwaController.hpp"

class NavigationTask : public RobotTask
{
public:
explicit NavigationTask(Robot * robot);
explicit NavigationTask(const std::string & name, Robot * robot);
NavigationTask() = delete;
~NavigationTask();

protected:
PlanningTask planner_;
ControlTask controller_;
AStarPlanner planner_;
DwaController controller_;
};

#endif // TASK__NAVIGATIONTASK_HPP_
10 changes: 6 additions & 4 deletions src/task/include/task/PlanningTask.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,16 +4,18 @@
#ifndef TASK__PLANNINGTASK_HPP_
#define TASK__PLANNINGTASK_HPP_

#include "task/RobotTask.hpp"
#include "task/Task.hpp"
#include "geometry_msgs/msg/pose_stamped.hpp"

class PlanningTask : public RobotTask
class PlanningTask : public Task
{
public:
explicit PlanningTask(Robot * robot);
PlanningTask(const std::string & name);
PlanningTask() = delete;
~PlanningTask();

// getPlan()
virtual void createPlan(const geometry_msgs::msg::PoseStamped & start,
const geometry_msgs::msg::PoseStamped & goal) = 0;
};

#endif // TASK__PLANNINGTASK_HPP_
2 changes: 1 addition & 1 deletion src/task/include/task/RobotTask.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
class RobotTask : public Task
{
public:
explicit RobotTask(Robot * robot);
RobotTask(const std::string & name, Robot * robot);
RobotTask() = delete;
~RobotTask();

Expand Down
28 changes: 18 additions & 10 deletions src/task/include/task/Task.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,22 +4,30 @@
#ifndef TASK__TASK_HPP_
#define TASK__TASK_HPP_

#include <atomic>
#include <thread>
#include <string>
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"

class Task
class Task: public rclcpp::Node
{
public:
virtual ~Task() {}
Task(const std::string & name);
virtual ~Task();

void execute();
void cancel();

protected:
// Emulate ROS Action for now:
// C++ templates for (Our)SimpleActionServer, (Our)SimpleActionClient
//
// * Subscriber for ROS topic for commands w/ parameters
// * Execute Command
// * Cancel Command
// * Publisher for status updates
// * Publisher for completion
virtual void workerThread() = 0;

std::thread *workerThread_;
std::atomic<bool> stopWorkerThread_;

void onCmdReceived(const std_msgs::msg::String::SharedPtr msg);

rclcpp::Subscription<std_msgs::msg::String>::SharedPtr cmdSub_;
};

#endif // TASK__TASK_HPP_
28 changes: 28 additions & 0 deletions src/task/src/AStarPlanner.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
// License: Apache 2.0. See LICENSE file in root directory.
// Copyright 2018 Intel Corporation. All Rights Reserved.

#include "task/AStarPlanner.hpp"

AStarPlanner::AStarPlanner(const std::string & name)
: PlanningTask(name)
{
RCLCPP_INFO(get_logger(), "AStarPlanner::AStarPlanner");
}

AStarPlanner::~AStarPlanner()
{
RCLCPP_INFO(get_logger(), "AStarPlanner::~AStarPlanner");
}

void
AStarPlanner::createPlan(const geometry_msgs::msg::PoseStamped & start,
const geometry_msgs::msg::PoseStamped & goal)
{
RCLCPP_INFO(get_logger(), "AStarPlanner::createPlan");
}

void
AStarPlanner::workerThread()
{
RCLCPP_INFO(get_logger(), "AStarPlanner::workerThread");
}
6 changes: 4 additions & 2 deletions src/task/src/ControlTask.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,11 +3,13 @@

#include "task/ControlTask.hpp"

ControlTask::ControlTask(Robot * robot)
: RobotTask(robot)
ControlTask::ControlTask(const std::string & name, Robot * robot)
: RobotTask(name, robot)
{
RCLCPP_INFO(get_logger(), "ControlTask::ControlTask");
}

ControlTask::~ControlTask()
{
RCLCPP_INFO(get_logger(), "ControlTask::~ControlTask");
}
27 changes: 27 additions & 0 deletions src/task/src/DwaController.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
// License: Apache 2.0. See LICENSE file in root directory.
// Copyright 2018 Intel Corporation. All Rights Reserved.

#include "task/DwaController.hpp"

DwaController::DwaController(const std::string & name, Robot * robot)
: ControlTask(name, robot)
{
RCLCPP_INFO(get_logger(), "DwaController::DwaController");
}

DwaController::~DwaController()
{
RCLCPP_INFO(get_logger(), "DwaController::~DwaController");
}

void
DwaController::executePlan()
{
RCLCPP_INFO(get_logger(), "DwaController::executePlan");
}

void
DwaController::workerThread()
{
RCLCPP_INFO(get_logger(), "DwaController::workerThread");
}
6 changes: 4 additions & 2 deletions src/task/src/NavigationTask.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,11 +3,13 @@

#include "task/NavigationTask.hpp"

NavigationTask::NavigationTask(Robot * robot)
: RobotTask(robot), planner_(robot), controller_(robot)
NavigationTask::NavigationTask(const std::string & name, Robot * robot)
: RobotTask(name, robot), planner_(name + "Planner"), controller_(name + "Controller", robot)
{
RCLCPP_INFO(get_logger(), "NavigationTask::NavigationTask");
}

NavigationTask::~NavigationTask()
{
RCLCPP_INFO(get_logger(), "NavigationTask::~NavigationTask");
}
6 changes: 4 additions & 2 deletions src/task/src/PlanningTask.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,11 +3,13 @@

#include "task/PlanningTask.hpp"

PlanningTask::PlanningTask(Robot * robot)
: RobotTask(robot)
PlanningTask::PlanningTask(const std::string & name)
: Task(name)
{
RCLCPP_INFO(get_logger(), "PlanningTask::PlanningTask");
}

PlanningTask::~PlanningTask()
{
RCLCPP_INFO(get_logger(), "PlanningTask::~PlanningTask");
}
5 changes: 4 additions & 1 deletion src/task/src/RobotTask.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,11 +3,14 @@

#include "task/RobotTask.hpp"

RobotTask::RobotTask(Robot * robot)
RobotTask::RobotTask(const std::string & name, Robot * robot)
: Task(name)
{
RCLCPP_INFO(get_logger(), "RobotTask::RobotTask");
robot = robot;
}

RobotTask::~RobotTask()
{
RCLCPP_INFO(get_logger(), "RobotTask::~RobotTask");
}
54 changes: 54 additions & 0 deletions src/task/src/Task.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,54 @@
// License: Apache 2.0. See LICENSE file in root directory.
// Copyright 2018 Intel Corporation. All Rights Reserved.

#include "task/Task.hpp"

Task::Task(const std::string & name)
: Node(name), workerThread_(nullptr), stopWorkerThread_(false)
{
RCLCPP_INFO(get_logger(), "Task::Task");

cmdSub_ = create_subscription<std_msgs::msg::String>("TaskCmd",
std::bind(&Task::onCmdReceived, this, std::placeholders::_1));
}

Task::~Task()
{
RCLCPP_INFO(get_logger(), "Task::~Task");
if (workerThread_ != nullptr)
cancel();
}

void
Task::execute()
{
RCLCPP_INFO(get_logger(), "Task::execute");
stopWorkerThread_ = false;
workerThread_ = new std::thread(&Task::workerThread, this);
}

void
Task::cancel()
{
RCLCPP_INFO(get_logger(), "Task::cancel");
stopWorkerThread_ = true;
workerThread_->join();

delete workerThread_;
workerThread_ = nullptr;
}

void
Task::onCmdReceived(const std_msgs::msg::String::SharedPtr msg)
{
RCLCPP_INFO(get_logger(), "Task::onCmdReceived: \"%s\"", msg->data.c_str())

if (msg->data.compare("ExecuteTask") == 0) {
execute();
} else if (msg->data.compare("CancelTask") == 0) {
cancel();
} else {
RCLCPP_INFO(get_logger(), "Task::onCmdReceived: invalid command: \"%s\"",
msg->data.c_str())
}
}

0 comments on commit 69a647c

Please sign in to comment.