ROS2学习记录--话题

1、如何查看话题的接口

ros2 topic info /turtle1/cmd_vel

2、话题发布数据:以小海龟为例修改线速度和角速度为例

ros2 topic pub /turtle1/cmd_vel geometry_msgs/msg/Twist "{linear: {x: 1.0, y: 0.0}, angular: {z: -1.0}}"

         注意:在冒号后面一定要加空格!!!

3、话题类型的功能包创建:

ros2 pkg create demo_python_topic --build-type ament_python --dependencies rclpy example_interfaces --license Apache-2.0

         节点类型的功能包创建:

ros2 pkg create demo_python_topic --build-type ament_python  --license Apache-2.0

         对功能包创建的解释:创建的所有参数都会写到package.xml文件中,创建的时候也可以先不指定,后续在package.xml文件中添加就行了。

4、cat命令:在终端显示文件内容

5、python自带的http服务器,它会将当前工作目录下的文件作为静态文件提供给浏览器。这个服务器默认监听在本地的 8000 端口上。

python3 -m http.server

 6、话题topic,框架如下图代码所示

import rclpy

from rclpy.node import Node

import requests

from example_interfaces.msg import String # 导入消息接口

from queue import Queue


 

class NovelPubNode(Node):

        def __init__(self, node_name):

        super().__init__(node_name)

        self.get_logger().info(f'{node_name}: 启动')

        self.novel_queue_ = Queue() # 创建队列

        self.novel_publisher_ = self.create_publisher(String, 'novel', 10) # 发送

        self.create_timer(5, self.timer_callback) # 定时发送中的定时

        def timer_callback(self):

                # self.novel_publisher_.publish()

                if self.novel_queue_.qsize() > 0:

                line = self.novel_queue_.get()

                msg = String() # 组装

                msg.data = line

                self.novel_publisher_.publish(msg)

                self.get_logger().info(f"发布了: {msg}")


 

           def download(self, url):

                response = requests.get(url)

                response.encoding = 'utf-8'

                text = response.text

                self.get_logger().info(f'开始下载{url}, {len(text)}')

                for line in text.splitlines():

                self.novel_queue_.put(line)


 

def main():

        rclpy.init()

        node = NovelPubNode("novel_pub_node")

        node.download("http://127.0.0.1:8000/novel1.txt")

        rclpy.spin(node)

        rclpy.shutdown()

7、如何判断Publisher是否创建成功

        新开一个中端,输入:

ros2 topic list # 找到你所需要的topic

ros2 topic echo /xxx # /xxx为你的topic

         则终端会在publisher发出消息的时候接收。

8、检查publisher的频率,以topic /novel为例。

ros2 topic hz /novel

9、创建c++功能包

ros2 pkg create demo_cpp_topic --build-type ament_cmake --dependencies rclcpp geometry_msgs turtlesim --license Apache-2.0

10、c++中的类通常先创建共享指针进行初始化赋值

11、c++小海龟画圈代码

        终端1:

ros2 run turtlesim turtlesim_node

        终端2:在工作空间文件夹下

source install/setup.bash
ros2 run demo_python_topic turtle_circle

         终端3:

        C++代码,turtle_circle文件: 

#include "rclcpp/rclcpp.hpp"
#include "geometry_msgs/msg/twist.hpp"
#include <chrono>

using namespace std::chrono_literals;

class TurtleCircleNode: public rclcpp::Node
{
private:
    rclcpp::TimerBase::SharedPtr timer_;
    rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr publisher_; //发布者的智能指针



public:
    explicit TurtleCircleNode(const std::string& node_name):Node(node_name)
    {
        publisher_ = this->create_publisher<geometry_msgs::msg::Twist>("/turtle1/cmd_vel", 10);
        timer_ = this->create_wall_timer(1000ms, std::bind(&TurtleCircleNode::timer_callback, this));
    }

    void timer_callback()
    {
        auto msg = geometry_msgs::msg::Twist();
        msg.linear.x = 1.0;
        msg.angular.z = 0.5;
        publisher_->publish(msg);
    }

};

int main(int argc, char* argv[])
{
    rclcpp::init(argc, argv);
    auto node = std::make_shared<TurtleCircleNode>("turtle_circle");
    rclcpp::spin(node);
    rclcpp::shutdown();
    return 0;
}

        CMAKE文件:

cmake_minimum_required(VERSION 3.8)
project(demo_cpp_topic)

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(geometry_msgs REQUIRED)
find_package(turtlesim REQUIRED)

add_executable(turtle_circle src/turtle_circle.cpp)

ament_target_dependencies(turtle_circle rclcpp geometry_msgs)



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

install(TARGETS turtle_circle
DESTINATION lib/${PROJECT_NAME}
)

ament_package()

12、需要在类里面加这句话,不然话题的消息发不出去:

publisher_->publish(msg);

13、查看功能包里某一种接口:以小海龟的姿态信息的接口为例:

ros2 interface show turtlesim/msg/Pose

14、fabs:c语言中计算保留浮点数的abs(绝对值)的函数

15、报错:AttributeError: 'SysStatusPub' object has no attribute '_logger'. Did you mean: 'get_logger'?

        原因:没有加上Node类的继承:

 super().__init__(node_name)

16、git的使用

  

git add xxxx添加到暂存区,可以是文件,也可以是文件夹。

git add . 将当前文件夹都添加到暂存区,不建议,因为log、install、build没啥用,所以只上传src最好

git commit -m "完成状态发布和显示功能" :提交暂存区中的代码

git log :查看历史的提交记录

ls -a:可以看到文件夹中有.git文件夹,rm -rf git就可以删除代码仓库。

        vscode中有源代码管理工具(左侧边栏),也可以可视化的帮我们管理代码。 

        .gitignore不仅可以忽略文件夹,还可以忽略某一类型的文件,在.gitignore文件中添加*.log就可以忽略.log类型的日志文件了。

评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值