ROS 基础语法速通(Noetic + Humble)——从 0 到能跑的完整示例
目录
ROS 术语速览:Node / Topic / Service / Action / Param / TF / Launch
最小工作区与功能包
消息 / 服务 / 动作语法(.msg / .srv / .action)
ROS1 Noetic 完整工程
ROS2 Humble 完整工程
常用命令速查(ROS1 vs ROS2)
典型坑位与一键自检清单
附录:代码阅读小抄(看到这些 API 代表什么)
1)ROS 术语速览
Node:进程。你的 C++/Python 程序就是节点。
Topic:发布-订阅(异步,流式)。“我一直在说/听”。
Service:请求-响应(同步,短事务)。“我问 → 你答”。
Action:长事务(可取消,带反馈)。“我下单 → 进度条 → 完成/失败”。
Param:参数(配置)。ROS1:集中参数服务器;ROS2:节点内参数。
TF/TF2:坐标变换树。
Launch:一键启动多个节点 + 注入参数。
2)最小工作区与功能包
ROS1 (catkin)
# 工作区
mkdir -p ~/demo_ws/src && cd ~/demo_ws && catkin_make
source devel/setup.bash
# 功能包(例:demo_pkg)
cd src && catkin_create_pkg demo_pkg roscpp std_msgs actionlib actionlib_msgs message_generation tf tf2_ros geometry_msgs && cd ..
catkin_make && source devel/setup.bashROS2 (colcon + ament)
mkdir -p ~/ros2_ws/src && cd ~/ros2_ws
ros2 pkg create --build-type ament_cmake demo_pkg \--dependencies rclcpp std_msgs rclcpp_action geometry_msgs tf2_ros tf2_msgs
colcon build && source install/setup.bash3)消息 / 服务 / 动作语法
下列文件放进 demo_pkg/ 的对应子目录。
msg/Person.msg
string name
uint8 age
float64 heightsrv/AddTwoInts.srv
int64 a
int64 b
---
int64 sumaction/Move.action
# goal
float64 dist
---
# result
uint8 RUNNING=0
uint8 SUCCESS=1
uint8 FAILURE=2
uint8 rc
---
# feedback
float64 run
uint8 rc| 文件 | 作用 | 通常使用的语法高亮语言 |
|---|---|---|
msg/Person.msg | ROS 自定义消息定义文件 (定义话题 message 数据结构) | ✅ Bash 或 None(纯文本), 因为 |
srv/AddTwoInts.srv | ROS Service 文件 (定义请求与响应的数据结构) | ✅ Bash 或 None(纯文本) |
action/Move.action | ROS Action 文件 (定义 Goal / Result / Feedback 三部分) | ✅ Bash 或 None(纯文本) |
要点:
常量可在 .msg/.srv/.action 内定义(如
SUCCESS=1)。数组:
float64[] ranges或定长int32[4] idx。Header:常用于
std_msgs/Header header(带时间戳/坐标系)。
4)ROS1 Noetic —— 完整工程
结构(仅关键文件):
demo_ws/src/demo_pkg/
├── action/Move.action
├── msg/Person.msg
├── srv/AddTwoInts.srv
├── launch/demo.launch
├── config/params.yaml
├── src/
│ ├── talker.cpp
│ ├── listener.cpp
│ ├── add_server.cpp
│ ├── add_client.cpp
│ ├── move_server.cpp
│ ├── move_client.cpp
│ └── static_tf_pub.cpp
├── package.xml
└── CMakeLists.txt4.1 package.xml(ROS1)
<?xml version="1.0"?>
<package format="2"><name>demo_pkg</name><version>0.0.1</version><description>ROS1 demo: topic/service/action/param/launch/tf</description><maintainer email="you@example.com">you</maintainer><license>MIT</license><buildtool_depend>catkin</buildtool_depend><build_depend>roscpp</build_depend><build_depend>std_msgs</build_depend><build_depend>message_generation</build_depend><build_depend>actionlib</build_depend><build_depend>actionlib_msgs</build_depend><build_depend>geometry_msgs</build_depend><build_depend>tf</build_depend><build_depend>tf2_ros</build_depend><exec_depend>roscpp</exec_depend><exec_depend>std_msgs</exec_depend><exec_depend>message_runtime</exec_depend><exec_depend>actionlib</exec_depend><exec_depend>actionlib_msgs</exec_depend><exec_depend>geometry_msgs</exec_depend><exec_depend>tf</exec_depend><exec_depend>tf2_ros</exec_depend>
</package>4.2 CMakeLists.txt(ROS1)
cmake_minimum_required(VERSION 3.0.2)
project(demo_pkg)find_package(catkin REQUIRED COMPONENTSroscpp std_msgs message_generation actionlib actionlib_msgs geometry_msgs tf tf2_ros
)## 消息/服务/动作接口
add_message_files(FILES Person.msg)
add_service_files(FILES AddTwoInts.srv)
add_action_files(DIRECTORY action FILES Move.action)## 代码生成
generate_messages(DEPENDENCIES std_msgs actionlib_msgs)catkin_package(CATKIN_DEPENDS roscpp std_msgs message_runtime actionlib actionlib_msgs)include_directories(${catkin_INCLUDE_DIRS})## 可执行文件
add_executable(talker src/talker.cpp)
add_executable(listener src/listener.cpp)
add_executable(add_server src/add_server.cpp)
add_executable(add_client src/add_client.cpp)
add_executable(move_server src/move_server.cpp)
add_executable(move_client src/move_client.cpp)
add_executable(static_tf_pub src/static_tf_pub.cpp)## 链接库
foreach(bin IN ITEMS talker listener add_server add_client move_server move_client static_tf_pub)target_link_libraries(${bin} ${catkin_LIBRARIES})add_dependencies(${bin} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
endforeach()4.3 配置与启动
config/params.yaml
gain: 1.2
hello_text: "hello from params"launch/demo.launch
<launch><!-- 批量参数加载 --><rosparam file="$(find demo_pkg)/config/params.yaml" command="load"/><node pkg="demo_pkg" type="talker" name="talker" output="screen"><param name="gain" value="1.5"/></node><node pkg="demo_pkg" type="listener" name="listener" output="screen"/><node pkg="demo_pkg" type="add_server" name="add_server" output="screen"/><node pkg="demo_pkg" type="add_client" name="add_client" output="screen"/><node pkg="demo_pkg" type="move_server" name="move_server" output="screen"/><node pkg="demo_pkg" type="move_client" name="move_client" output="screen"/><!-- 等价于 static_transform_publisher 0 0 0 0 0 0 1 map base_link 10 --><node pkg="demo_pkg" type="static_tf_pub" name="static_tf_pub" output="screen"/>
</launch>4.4 源码(ROS1)
src/talker.cpp(Topic 发布 + 读取参数)
#include <ros/ros.h>
#include <std_msgs/String.h>
#include <sstream>
int main(int argc, char** argv){ros::init(argc, argv, "talker");ros::NodeHandle nh("~"); // 私有命名空间参数 ~gaindouble gain = 1.0; nh.param("gain", gain, 1.0);ros::Publisher pub = nh.advertise<std_msgs::String>("/chatter", 10);ros::Rate rate(5);int i=0;while(ros::ok()){std_msgs::String msg; std::stringstream ss; ss << "hello #"<< i++ << " (gain="<<gain<<")";msg.data = ss.str();pub.publish(msg);ros::spinOnce(); rate.sleep();}return 0;
}src/listener.cpp(Topic 订阅)
#include <ros/ros.h>
#include <std_msgs/String.h>
void cb(const std_msgs::String::ConstPtr& msg){ROS_INFO_STREAM("[listener] " << msg->data);
}
int main(int argc, char** argv){ros::init(argc, argv, "listener");ros::NodeHandle nh;auto sub = nh.subscribe("/chatter", 10, cb);ros::spin();
}src/add_server.cpp(Service 服务端)
#include <ros/ros.h>
#include <demo_pkg/AddTwoInts.h>bool add(demo_pkg::AddTwoInts::Request& req, demo_pkg::AddTwoInts::Response& res){res.sum = req.a + req.b;ROS_INFO("AddTwoInts: %ld + %ld = %ld", (long)req.a, (long)req.b, (long)res.sum);return true;
}
int main(int argc, char** argv){ros::init(argc, argv, "add_server");ros::NodeHandle nh;auto srv = nh.advertiseService("/add_two_ints", add);ros::spin();
}src/add_client.cpp(Service 客户端)
#include <ros/ros.h>
#include <demo_pkg/AddTwoInts.h>
int main(int argc, char** argv){ros::init(argc, argv, "add_client");ros::NodeHandle nh;ros::ServiceClient client = nh.serviceClient<demo_pkg::AddTwoInts>("/add_two_ints");demo_pkg::AddTwoInts srv; srv.request.a = 10; srv.request.b = 20;if(client.call(srv)) ROS_INFO("sum=%ld", (long)srv.response.sum);else ROS_ERROR("Failed to call service");
}src/move_server.cpp(Action 服务器)
#include <ros/ros.h>
#include <actionlib/server/simple_action_server.h>
#include <demo_pkg/MoveAction.h>class MoveServer{ros::NodeHandle nh_;actionlib::SimpleActionServer<demo_pkg::MoveAction> as_;std::string name_;
public:MoveServer(std::string name):nh_(""), as_(nh_, name, boost::bind(&MoveServer::executeCB, this, _1), false), name_(name){as_.start();}void executeCB(const demo_pkg::MoveGoalConstPtr& goal){demo_pkg::MoveFeedback fb; demo_pkg::MoveResult res;fb.traveled = 0.0; fb.rc = demo_pkg::MoveResult::RUNNING;ros::Rate r(10);double step = goal->reverse ? -0.05 : 0.05; // 每次 5cmwhile(ros::ok()){if(as_.isPreemptRequested()){res.rc = demo_pkg::MoveResult::FAILURE; as_.setPreempted(res, "preempted"); return;}fb.traveled += step; if((!goal->reverse && fb.traveled >= goal->distance) || (goal->reverse && fb.traveled <= -goal->distance)){res.rc = demo_pkg::MoveResult::SUCCESS; as_.setSucceeded(res, "done"); return;}as_.publishFeedback(fb); r.sleep();}}
};
int main(int argc, char** argv){ ros::init(argc, argv, "move_server"); MoveServer s("/move"); ros::spin(); }src/move_client.cpp(Action 客户端)
#include <ros/ros.h>
#include <actionlib/client/simple_action_client.h>
#include <demo_pkg/MoveAction.h>int main(int argc, char** argv){ros::init(argc, argv, "move_client");actionlib::SimpleActionClient<demo_pkg::MoveAction> ac("/move", true);ac.waitForServer();demo_pkg::MoveGoal goal; goal.distance = 1.0; goal.reverse = false;ac.sendGoal(goal,// done[](const actionlib::SimpleClientGoalState& state, const demo_pkg::MoveResultConstPtr& res){ROS_INFO("Done. state=%s rc=%u", state.toString().c_str(), res->rc);},// active[](){ ROS_INFO("Goal active"); },// feedback[](const demo_pkg::MoveFeedbackConstPtr& fb){ ROS_INFO("traveled=%.2f rc=%u", fb->traveled, fb->rc); });ac.waitForResult();
}src/static_tf_pub.cpp(发布静态 TF)
#include <ros/ros.h>
#include <tf/transform_broadcaster.h>
int main(int argc, char** argv){ros::init(argc, argv, "static_tf_pub");static tf::TransformBroadcaster br;tf::Transform t; t.setOrigin(tf::Vector3(0,0,0)); t.setRotation(tf::Quaternion(0,0,0,1));ros::Rate r(10);while(ros::ok()){br.sendTransform(tf::StampedTransform(t, ros::Time::now(), "map", "base_link"));r.sleep();}
}4.5 编译与运行(ROS1)
cd ~/demo_ws && catkin_make && source devel/setup.bash
roslaunch demo_pkg demo.launchCLI 验证
# Topic
rostopic list
rostopic echo /chatter# Service
rosservice list
rosservice call /add_two_ints "a: 3 b: 5"# Action
rostopic echo /move/feedback
rostopic echo /move/status# TF 可视化(任选其一)
rosrun rqt_tf_tree rqt_tf_tree5)ROS2 Humble —— 完整工程
结构(仅关键文件):
ros2_ws/src/demo_pkg/
├── msg/Person.msg
├── srv/AddTwoInts.srv
├── action/Move.action
├── launch/demo_launch.py
├── src/
│ ├── talker.cpp
│ ├── listener.cpp
│ ├── add_server.cpp
│ ├── add_client.cpp
│ ├── move_server.cpp
│ ├── move_client.cpp
│ └── static_tf_pub.cpp
├── CMakeLists.txt
└── package.xml5.1 package.xml(ROS2)
<?xml version="1.0"?>
<package format="3"><name>demo_pkg</name><version>0.0.1</version><description>ROS2 demo</description><maintainer email="you@example.com">you</maintainer><license>MIT</license><buildtool_depend>ament_cmake</buildtool_depend><depend>rclcpp</depend><depend>std_msgs</depend><depend>rclcpp_action</depend><depend>geometry_msgs</depend><depend>tf2_ros</depend><depend>rosidl_default_runtime</depend><build_depend>rosidl_default_generators</build_depend>
</package>5.2 CMakeLists.txt(ROS2)
cmake_minimum_required(VERSION 3.8)
project(demo_pkg)find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
find_package(rclcpp_action REQUIRED)
find_package(tf2_ros REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(rosidl_default_generators REQUIRED)# 接口生成
rosidl_generate_interfaces(${PROJECT_NAME}"msg/Person.msg""srv/AddTwoInts.srv""action/Move.action"DEPENDENCIES std_msgs
)# 可执行文件
add_executable(talker src/talker.cpp)
ament_target_dependencies(talker rclcpp std_msgs)add_executable(listener src/listener.cpp)
ament_target_dependencies(listener rclcpp std_msgs)add_executable(add_server src/add_server.cpp)
ament_target_dependencies(add_server rclcpp)add_executable(add_client src/add_client.cpp)
ament_target_dependencies(add_client rclcpp)add_executable(move_server src/move_server.cpp)
ament_target_dependencies(move_server rclcpp rclcpp_action)add_executable(move_client src/move_client.cpp)
ament_target_dependencies(move_client rclcpp rclcpp_action)add_executable(static_tf_pub src/static_tf_pub.cpp)
ament_target_dependencies(static_tf_pub rclcpp tf2_ros)install(TARGETS talker listener add_server add_client move_server move_client static_tf_pubDESTINATION lib/${PROJECT_NAME})ament_package()5.3 Launch(ROS2)
launch/demo_launch.py
from launch import LaunchDescription
from launch_ros.actions import Nodedef generate_launch_description():return LaunchDescription([Node(package='demo_pkg', executable='talker', name='talker', output='screen',parameters=[{'gain': 1.5, 'hello_text': 'hello from params'}]),Node(package='demo_pkg', executable='listener', name='listener', output='screen'),Node(package='demo_pkg', executable='add_server', name='add_server', output='screen'),Node(package='demo_pkg', executable='add_client', name='add_client', output='screen'),Node(package='demo_pkg', executable='move_server', name='move_server', output='screen'),Node(package='demo_pkg', executable='move_client', name='move_client', output='screen'),Node(package='demo_pkg', executable='static_tf_pub', name='static_tf_pub', output='screen'),])5.4 源码(ROS2)
src/talker.cpp
#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/string.hpp>int main(int argc, char** argv){rclcpp::init(argc, argv);auto node = rclcpp::Node::make_shared("talker");double gain = node->declare_parameter<double>("gain", 1.0);auto pub = node->create_publisher<std_msgs::msg::String>("/chatter", 10);rclcpp::WallRate rate(5);int i=0;while(rclcpp::ok()){std_msgs::msg::String m; m.data = "hello #" + std::to_string(i++) + " (gain=" + std::to_string(gain) + ")";pub->publish(m);rclcpp::spin_some(node); rate.sleep();}rclcpp::shutdown();
}src/listener.cpp
#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/string.hpp>
int main(int argc, char** argv){rclcpp::init(argc, argv);auto node = rclcpp::Node::make_shared("listener");auto sub = node->create_subscription<std_msgs::msg::String>("/chatter", 10,[](std_msgs::msg::String::ConstSharedPtr m){ RCLCPP_INFO(node->get_logger(), "%s", m->data.c_str()); });rclcpp::spin(node); rclcpp::shutdown();
}src/add_server.cpp
#include <rclcpp/rclcpp.hpp>
#include "demo_pkg/srv/add_two_ints.hpp"int main(int argc, char** argv){rclcpp::init(argc, argv);auto node = rclcpp::Node::make_shared("add_server");auto srv = node->create_service<demo_pkg::srv::AddTwoInts>("/add_two_ints",[](const std::shared_ptr<demo_pkg::srv::AddTwoInts::Request> req,std::shared_ptr<demo_pkg::srv::AddTwoInts::Response> res){ res->sum = req->a + req->b; });rclcpp::spin(node); rclcpp::shutdown();
}src/add_client.cpp
#include <rclcpp/rclcpp.hpp>
#include "demo_pkg/srv/add_two_ints.hpp"int main(int argc, char** argv){rclcpp::init(argc, argv);auto node = rclcpp::Node::make_shared("add_client");auto client = node->create_client<demo_pkg::srv::AddTwoInts>("/add_two_ints");while(!client->wait_for_service(std::chrono::seconds(1))){}auto req = std::make_shared<demo_pkg::srv::AddTwoInts::Request>(); req->a=10; req->b=20;auto res = client->async_send_request(req);if(auto r = rclcpp::spin_until_future_complete(node, res); r==rclcpp::FutureReturnCode::SUCCESS){RCLCPP_INFO(node->get_logger(), "sum=%ld", (long)res.get()->sum);}rclcpp::shutdown();
}src/move_server.cpp
#include <rclcpp/rclcpp.hpp>
#include <rclcpp_action/rclcpp_action.hpp>
#include "demo_pkg/action/move.hpp"class MoveServer : public rclcpp::Node{
public:using Move = demo_pkg::action::Move;using GoalHandle = rclcpp_action::ServerGoalHandle<Move>;MoveServer(): Node("move_server"){server_ = rclcpp_action::create_server<Move>(this, "move",std::bind(&MoveServer::handle_goal, this, std::placeholders::_1, std::placeholders::_2),std::bind(&MoveServer::handle_cancel, this, std::placeholders::_1),std::bind(&MoveServer::handle_accepted, this, std::placeholders::_1));}
private:rclcpp_action::Server<Move>::SharedPtr server_;rclcpp_action::GoalResponse handle_goal(const rclcpp_action::GoalUUID&, std::shared_ptr<const Move::Goal>){return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;}rclcpp_action::CancelResponse handle_cancel(const std::shared_ptr<GoalHandle>){return rclcpp_action::CancelResponse::ACCEPT;}void handle_accepted(const std::shared_ptr<GoalHandle> gh){std::thread([this, gh](){auto fdbk = std::make_shared<Move::Feedback>();auto res = std::make_shared<Move::Result>();rclcpp::Rate r(10);double traveled = 0.0; double step = gh->get_goal()->reverse ? -0.05 : 0.05;while(rclcpp::ok()){if(gh->is_canceling()){ res->rc = Move::Result::FAILURE; gh->canceled(res); return; }traveled += step;fdbk->traveled = traveled; fdbk->rc = Move::Result::RUNNING; gh->publish_feedback(fdbk);if((!gh->get_goal()->reverse && traveled >= gh->get_goal()->distance) || (gh->get_goal()->reverse && traveled <= -gh->get_goal()->distance)){res->rc = Move::Result::SUCCESS; gh->succeed(res); return;}r.sleep();}}).detach();}
};
int main(int argc, char** argv){ rclcpp::init(argc, argv); rclcpp::spin(std::make_shared<MoveServer>()); rclcpp::shutdown(); }src/move_client.cpp
#include <rclcpp/rclcpp.hpp>
#include <rclcpp_action/rclcpp_action.hpp>
#include "demo_pkg/action/move.hpp"int main(int argc, char** argv){rclcpp::init(argc, argv); auto node = rclcpp::Node::make_shared("move_client");using Move = demo_pkg::action::Move;auto client = rclcpp_action::create_client<Move>(node, "move");client->wait_for_action_server();Move::Goal goal; goal.distance = 1.0; goal.reverse = false;auto send_goal_opts = rclcpp_action::Client<Move>::SendGoalOptions();send_goal_opts.feedback_callback = [node](auto, auto fb){ RCLCPP_INFO(node->get_logger(), "traveled=%.2f rc=%u", fb->traveled, fb->rc); };auto future_handle = client->async_send_goal(goal, send_goal_opts);auto handle_res = rclcpp::spin_until_future_complete(node, future_handle);auto result_future = client->async_get_result(future_handle.get());rclcpp::spin_until_future_complete(node, result_future);rclcpp::shutdown();
}src/static_tf_pub.cpp
#include <rclcpp/rclcpp.hpp>
#include <tf2_ros/static_transform_broadcaster.h>
#include <geometry_msgs/msg/transform_stamped.hpp>int main(int argc, char** argv){rclcpp::init(argc, argv); auto node = rclcpp::Node::make_shared("static_tf_pub");tf2_ros::StaticTransformBroadcaster br(node);geometry_msgs::msg::TransformStamped t; t.header.frame_id = "map"; t.child_frame_id = "base_link"; t.transform.rotation.w = 1.0;t.header.stamp = node->now(); br.sendTransform(t);rclcpp::spin(node); rclcpp::shutdown();
}5.5 编译与运行(ROS2)
cd ~/ros2_ws && colcon build && source install/setup.bash
ros2 launch demo_pkg demo_launch.pyCLI 验证
ros2 topic list
ros2 topic echo /chatter
ros2 service call /add_two_ints demo_pkg/srv/AddTwoInts "{a: 3, b: 5}"
ros2 action list
ros2 action info /move6)常用命令速查
| 场景 | ROS1 | ROS2 | |
|---|---|---|---|
| 节点列表 | rosnode list | ros2 node list | |
| 话题列表/回显 | rostopic list/echo | ros2 topic list/echo | |
| 发布话题 | rostopic pub /xx type '{...}' | ros2 topic pub /xx pkg/msg/Type '{...}' | |
| 服务列表/调用 | rosservice list/call | ros2 service list/call | |
| 动作列表/信息 | `rostopic list | grep goal`(或 rqt) | ros2 action list/info |
| 参数 | rosparam get/set/load | ros2 param get/set/list | |
| 录包/回放 | rosbag record/play | ros2 bag record/play | |
| TF 可视化 | rosrun rqt_tf_tree rqt_tf_tree | ros2 run tf2_tools view_frames |
7)典型坑位与一键自检清单
编译成功但找不到头文件:是否
source devel/setup.bash(ROS1)/source install/setup.bash(ROS2)?VSCode 终端是否在正确环境?消息/服务/动作未生成:ROS1 是否写了
add_*_files+generate_messages+catkin_package(CATKIN_DEPENDS message_runtime ...);ROS2 是否有rosidl_generate_interfaces与rosidl_default_runtime依赖?Action 常量:使用生成后的命名空间(如
Move::Result::SUCCESS)。参数为啥拿不到:ROS2 需先
declare_parameter;ROS1 注意~param与全局命名空间。多工作区/Overlay 混乱:
echo $CMAKE_PREFIX_PATH检查顺序;必要时开干净终端,只 source 目标工作区。话题名对不上:
ros{,2} topic list看看真名;带/不带前缀要统一。
8)附录:代码阅读小抄
ROS1:
ros::init/ros::NodeHandle/advertise/subscribe/ServiceServer/SimpleActionServer/ros::spin()/Rate。ROS2:
rclcpp::Node::make_shared/create_publisher/create_subscription/create_service/rclcpp_action/spin/declare_parameter。CMake(ROS1):
message_generation+generate_messages+catkin_package三件套。CMake(ROS2):
rosidl_generate_interfaces+ament_target_dependencies+install(TARGETS ...)。
