Skip to content

Commit

Permalink
#1 update basic setting for ros2
Browse files Browse the repository at this point in the history
  • Loading branch information
dongdongO committed Mar 18, 2024
1 parent 7c2790a commit edf2b41
Show file tree
Hide file tree
Showing 8 changed files with 238 additions and 1 deletion.
1 change: 0 additions & 1 deletion README.md

This file was deleted.

5 changes: 5 additions & 0 deletions control/.gitignore
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
.vscode
build
log
install
.DStore
56 changes: 56 additions & 0 deletions control/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
cmake_minimum_required(VERSION 3.5)
project(control)

# Default to C99
if(NOT CMAKE_C_STANDARD)
set(CMAKE_C_STANDARD 99)
endif()

# Default to C++14
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

# find dependencies
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
find_package(nav_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(ackermann_msgs REQUIRED)
find_package(tf2 REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)
# uncomment the following section in order to fill in
# further dependencies manually.
# find_package(<dependency> REQUIRED)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
# uncomment the line when a copyright and license is not present in all source files
#set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)
# uncomment the line when this package is not in a git repo
#set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()

ament_package()

include_directories(
include/${PROJECT_NAME}
)

add_executable(${PROJECT_NAME}
src/main.cpp
src/control.cpp
)
ament_target_dependencies(${PROJECT_NAME} rclcpp nav_msgs ackermann_msgs tf2 tf2_geometry_msgs)

install(TARGETS
${PROJECT_NAME}
DESTINATION lib/${PROJECT_NAME})
50 changes: 50 additions & 0 deletions control/include/control/control.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
#pragma once

#include "msg_structs.h"

#include "rclcpp/rclcpp.hpp"
#include "nav_msgs/msg/path.hpp"
#include "std_msgs/msg/int8.hpp"
#include "geometry_msgs/msg/pose_stamped.hpp"
// #include "nav_msgs/msg/odometry.hpp"

#include "ackermann_msgs/msg/ackermann_drive_stamped.hpp"
#include "tf2/LinearMath/Quaternion.h"
#include <tf2/LinearMath/Matrix3x3.h>
#include <tf2/convert.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>

#include <string>
#include <cmath>

class Control : public rclcpp::Node {
public:
Control();

private:
std::vector<Pose> refPoses;
Pose currPose;
int currVel;
bool currDirection;

float speedCommand;
float steerCommand;

bool velocityValid;
bool poseValid;

rclcpp::Publisher<ackermann_msgs::msg::AckermannDriveStamped>::SharedPtr drive_publisher_;
rclcpp::Subscription<nav_msgs::msg::Path>::SharedPtr path_subscription_;
rclcpp::Subscription<std_msgs::msg::Int8>::SharedPtr velocity_subscription_;
rclcpp::Subscription<geometry_msgs::msg::PoseStamped>::SharedPtr pose_subscription_;
// rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr pose_subscription_;
rclcpp::TimerBase::SharedPtr publisher_timer_;

void path_callback(const nav_msgs::msg::Path::SharedPtr path_msg);
void velocity_callback(const std_msgs::msg::Int8::SharedPtr velocity_msg);
void pose_callback(const geometry_msgs::msg::PoseStamped::SharedPtr pose_msg);
// void pose_callback(const nav_msgs::msg::Odometry::SharedPtr pose_msg);
void publisher_timer_callback();
void publish_drive(float speed, float steer);
float quat_to_yaw(const geometry_msgs::msg::Quaternion quat_msg);
};
9 changes: 9 additions & 0 deletions control/include/control/msg_structs.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
#pragma once

#include <string>

struct Pose {
float x;
float y;
float heading;
};
26 changes: 26 additions & 0 deletions control/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>control</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="tjehdghks4356@gmail.com">dongdongo</maintainer>
<license>TODO: License declaration</license>

<buildtool_depend>ament_cmake</buildtool_depend>

<depend>rclcpp</depend>
<depend>nav_msgs</depend>
<depend>std_msgs</depend>
<depend>geometry_msgs</depend>
<depend>ackermann_msgs</depend>
<depend>tf2</depend>
<depend>tf2_geometry_msgs</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>
83 changes: 83 additions & 0 deletions control/src/control.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,83 @@
#include "control.h"

Control::Control() : rclcpp::Node("vehicle_control") {
// Subscribe
path_subscription_ = this->create_subscription<nav_msgs::msg::Path>(
"/planner/path", 10, std::bind(&Control::path_callback, this, std::placeholders::_1));
velocity_subscription_ = this->create_subscription<std_msgs::msg::Int8>(
"/planner/velocity", 10, std::bind(&Control::velocity_callback, this, std::placeholders::_1));
// pose_subscription_ = this->create_subscription<geometry_msgs::msg::PoseStamped>(
// "/localization/pose", 10, std::bind(&Control::pose_callback, this, std::placeholders::_1));

// Publish
drive_publisher_ = this->create_publisher<ackermann_msgs::msg::AckermannDriveStamped>(
"/controller/drive", 10);

publisher_timer_ = this->create_wall_timer(
std::chrono::milliseconds(100),
std::bind(&Control::publisher_timer_callback, this)
);
}

void Control::path_callback(const nav_msgs::msg::Path::SharedPtr path_msg) {
this->refPoses.clear();
Pose refPose;
for (size_t i = 0; i < path_msg->poses.size(); ++i) {
refPose.x = path_msg->poses[i].pose.position.x;
refPose.y = path_msg->poses[i].pose.position.y;
refPose.heading = this->quat_to_yaw(path_msg->poses[i].pose.orientation);
this->refPoses.push_back(refPose);
}
// this->controller.resetIndex(0);
}

void Control::velocity_callback(const std_msgs::msg::Int8::SharedPtr velocity_msg) {
this->velocityValid = false;
this->currVel = velocity_msg->data;
if (this->currVel >= 0) {this->currDirection = true;}
else {this->currDirection = false;}
this->velocityValid = true;
}

// void Control::pose_callback(const geometry_msgs::msg::PoseStamped::SharedPtr pose_msg) {
// this->poseValid = false;
// this->currPose.x = pose_msg->pose.position.x;
// this->currPose.y = pose_msg->pose.position.y;
// this->currPose.heading = this->quat_to_yaw(pose_msg->pose.orientation);
// this->poseValid = true;
// }

void Control::publisher_timer_callback() {
// if (this->refPoses.empty() || !this->poseValid || !this->velocityValid) {return;}

// // this->controller.calculateControl(refPoses, currPose, currVel, currDirection);
// this->speedCommand = this->controller.getSpeedCommand();
// this->steerCommand = - this->controller.getSteerCommand() * 180 / M_PI;
// // this->steerCommand = 0.5*this->controller.getSteerCommand() + 0.5*this->steerCommand;

// this->publish_drive(this->speedCommand, this->steerCommand);
}

void Control::publish_drive(float speed, float steer) {
ackermann_msgs::msg::AckermannDriveStamped drive_msg;

drive_msg.header = std_msgs::msg::Header();
drive_msg.header.stamp = rclcpp::Clock().now();
drive_msg.header.frame_id = "map";

drive_msg.drive.speed = speed;
drive_msg.drive.steering_angle = steer;

this->drive_publisher_->publish(drive_msg);
}

float Control::quat_to_yaw(const geometry_msgs::msg::Quaternion quat) {
tf2::Quaternion tf2_quat;
tf2::fromMsg(quat, tf2_quat);
double roll;
double pitch;
double yaw;
tf2::Matrix3x3 matrix(tf2_quat);
matrix.getRPY(roll, pitch, yaw);
return yaw;
}
9 changes: 9 additions & 0 deletions control/src/main.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
#include "control.h"

int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<Control>());
rclcpp::shutdown();
return 0;
}

0 comments on commit edf2b41

Please sign in to comment.