2024-07-15T05:24:35.png

1.第一次需新建并设置工作空间,在home目录下

mkdir -p ros2_ws/src  # -p可以创建多重目录,无需一级一级创建
cd ros2_ws # 进入工作空间
colcon build # 编译一次
source install/local_setup.bash # 位置声明

2.创建乌龟走方块的程序包

cd ros2_ws/src # 进入程序目录
ros2 pkg create --build-type ament_cmake turtlesim_square --dependencies rclcpp  geometry_msgs # 创建一个c程序的新包,名为turtlesim_square

3.编写C程序

mkdir -p ros2_ws/src/turtlesim_square/src
cd ros2_ws/src/turtlesim_square/src
nano turtlesim_square.cpp

添加以下内容后 ctrl+X , y ,回车。
程序内容为:

#include <chrono>
#include <memory>

#include "rclcpp/rclcpp.hpp"
#include "geometry_msgs/msg/twist.hpp"

using namespace std::chrono_literals;

class TurtleSimSquare : public rclcpp::Node
{
public:
  TurtleSimSquare() : Node("turtlesim_square")
  {
    publisher_ = this->create_publisher<geometry_msgs::msg::Twist>("turtle1/cmd_vel", 10);
    timer_ = this->create_wall_timer(1000ms, std::bind(&TurtleSimSquare::timer_callback, this));
    step_ = 0;
  }

private:
  void timer_callback()
  {
    auto message = geometry_msgs::msg::Twist();
    if (step_ % 2 == 0) {
      // Move forward
      message.linear.x = 2.0;
      message.angular.z = 0.0;
    } else {
      // Turn
      message.linear.x = 0.0;
      message.angular.z = 1.57; // 90 degrees in radians
    }

    publisher_->publish(message);

    // Increase step counter
    step_++;
    if (step_ >= 8) {
      // Stop the turtle after completing the square
      timer_->cancel();
    }
  }

  rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr publisher_;
  rclcpp::TimerBase::SharedPtr timer_;
  int step_;
};

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

4.更新CMakeLists.txt

cd ..
nano CMakeLists.txt
# 在install前加入以下两行,然后 ctrl+X , y ,回车。
add_executable(turtlesim_square src/turtlesim_square.cpp)
ament_target_dependencies(turtlesim_square rclcpp geometry_msgs)

5.编译和运行

回到你的工作空间目录并编译:

cd ros2_ws
colcon build
source install/local_setup.bash

启动Turtlesim节点:

ros2 run turtlesim turtlesim_node

然后,在另一个终端中运行你的正方形轨迹程序:

cd ros2_ws
source install/local_setup.bash
ros2 run turtlesim_square turtlesim_square

这样,小乌龟就会按照一个正方形轨迹移动。每一个方向的直线行走和转弯都会交替进行,完成一个完整的正方形后,程序会停止。

发表评论