接上一节,
======= 开始用Eclipse写一个发布给Turtlesim_node驱动和角度Msg的 my_node1 =====
参考Youtube上两个视频:
[CS460] ROS Tutorial 4.1 Turtlesim Cleaner Application - An Overview
[CS460] ROS Tutorial 4.2 Moving in a Straight Line (Turtlesim Cleaner)
2015年7月21日09:59:26
建立一个名为robot_cleaner的Package,生成robot_cleaner_node,向turtlesim_node发送msg.
topic info:
topic_name: /turtle1/cmd_vel
topic_type: geometry_msgs/Twist
Message info:
$ rosmsg show geometry_msgs/Twist
show the data struct:
geometry_msgs/Vector3 linear
float64 x
float64 y
float64 z
geometry_msgs/Vector3 angular
float64 x
float64 y
float64 z
$ rostopic echo /turtle1/cmd_vel
得到:
linear:
x: 0.0
y: 0.0
z: 0.0
angular:
x: 0.0
y: 0.0
z: 2.0
Package Dependency:
roscpp
rospy
std_msgs
geometry_msgs
message_generation
===============
1. Create the Package:
$ cd ~/catkin_ws/src/ $ catkin_create_pkg robot_cleaner roscpp rospy std_msgs geometry_msgs message_generation
2. Generate the Eclipse Files for dev. in Eclipse IDE
$ cd ~/catkin_ws //这实际上是Workspace的路径,catkin_ws = catkin workspace $ catkin_make --force-cmake -G"Eclipse CDT4 - Unix Makefiles" $ . ~/catkin_ws/devel/setup.bash
to generate the .project file and then run:
$ awk -f $(rospack find mk)/eclipse.awk build/.project > build/.project_with_env && mv build/.project_with_env build/.project
此时刷新Eclipse里的Project Explorer,可以看到“robot_cleaner”这个项目。
【问题】: 为何要在Terminal里建立Package再生成Eclipse File,不能直接在Eclipse里创建Package么?怎么创建?
3. 在Eclipse里创建cpp源文件
Project@Build -> [Source directory] -> robot_cleaner ->src ->单击鼠标右键-> new ->file ->File name:robot_cleaner.cpp
[如图片]:
4. 编辑cpp源文件
/* File: robot_cleaner.cpp
* source file
* auther : sonic
*
*/
#include "ros/ros.h"
#include "geometry_msgs/Twist.h"
ros::Publisher velocity_publisher; //Declare a ros Publisher: velocity_publisher
//Declare the method to move the robot straight
void move(double speed, double distance, bool isForward);
int main(int argc, char **argv){
//Initiate new ROS node named "talker"
ros::init(argc, argv, "robot_cleaner");
ros::NodeHandle n;
ROS_INFO("Your robot cleaner node starts!"); //打印,用于调试。
velocity_publisher = n.advertise<geometry_msgs::Twist>("/turtle1/cmd_vel",10); //initiate the ros publisher
move(2.0, 5.0, 1);
}
//Definition of the method move()
void move(double speed, double distance, bool isForward){
geometry_msgs::Twist vel_msg;
//distance = speed * time
//set a random linear velocity in the x-axis
if (isForward)
vel_msg.linear.x = abs(speed);
else
vel_msg.linear.x = -abs(speed);
vel_msg.linear.y = 0;
vel_msg.linear.z = 0;
//set a random angular velocity in the y-axis
vel_msg.angular.x = 0;
vel_msg.angular.y = 0;
vel_msg.angular.z = 0;
//t0: the current time
double t0 = ros::Time::now().toSec();
double current_distance = 0;
ros::Rate loop_rate(10);
do{
velocity_publisher.publish(vel_msg);
double t1 = ros::Time::now().toSec();
current_distance = speed * (t1 - t0);
ros::spinOnce();
loop_rate.sleep();
}while (current_distance < distance);
vel_msg.linear.x = 0; //stop it
velocity_publisher.publish(vel_msg);
//loop
//publish the velocity
//estimate the distance = speed *(t1-t0)
//current_distance_moved_by_robot <= distance
}
5. 修改Catkin Make List文件
文件: CMakelists.txt
加入如下代码:
add_executable(robot_cleaner_node src/robot_cleaner.cpp) #specify which cpp should be compile and create the execute
target_link_libraries(robot_cleaner_node ${catkin_LIBRARIES})
add_dependencies(robot_cleaner_node robot_cleaner_gencpp)
6. 编译、运行和调试你的executables
Eclipse -> Project -> Build Project...
7. 运行和调试你的executables
先来看看能不能动哈:
$ rosrun turtlesim turtlesim_node
$ rosrun robot_cleaner robot_cleaner_node
我们看到robot_cleaner_node 打印出:“The robot cleaner node starts!”, 并且乌龟向右移动了。
OK, 至此,我们就完成了一个可以发布geometry_msg的node.
练习1:让turtle画个圆,如何?
练习2:让turtle走到pose = 特定位置的点,怎么弄?(涉及到从turtlesim_node接收topic="/turtle1/pose"的信息,并实时规划linear.x 和 angular.z 的值)
欢迎通过评论提交各位的代码~ :)

本文档详细介绍了如何使用Eclipse进行ROS的robot_cleaner包开发,包括创建package,生成Eclipse项目文件,编写cpp源文件,编辑Catkin MakeLists文件,并进行编译、运行和调试executables。内容中还提到了练习,如让turtle画圆和走到特定位置。
7693

被折叠的 条评论
为什么被折叠?



