1 写在前面
笔者近期学习了《ROS by Example. Do-It-Yourself Guide to the Robot Operating System》,书中的代码全部是用python来编写的,为了保证完全理解其代码的含义及代码背后的相关知识,这里我将其代码用C++实现了一遍,写下此文章用作记录存留。
2 主要内容
本文对应第7.8章节中的内容,实现了 nav_square.py 到 nav_square.cpp 的转换。
开发环境:Ubuntu14.04 + ROS-Indigo
3 原始python脚本
nav_square.py
import rospy
from geometry_msgs.msg import Twist, Point, Quaternion
import tf
from rbx1_nav.transform_utils import quat_to_angle, normalize_angle
from math import radians, copysign, sqrt, pow, pi
class NavSquare():
def __init__(self):
rospy.init_node('nav_square', anonymous=False)
rospy.on_shutdown(self.shutdown)
rate = 20
r = rospy.Rate(rate)
goal_distance = rospy.get_param("~goal_distance", 1.0)
goal_angle = radians(rospy.get_param("~goal_angle", 90))
linear_speed = rospy.get_param("~linear_speed", 0.2)
angular_speed = rospy.get_param("~angular_speed", 0.7)
angular_tolerance = radians(rospy.get_param("~angular_tolerance", 2))
self.cmd_vel = rospy.Publisher('/cmd_vel', Twist, queue_size=5)
self.base_frame = rospy.get_param('~base_frame', '/base_link')
self.odom_frame = rospy.get_param('~odom_frame', '/odom')
self.tf_listener = tf.TransformListener()
rospy.sleep(2)
self.odom_frame = '/odom'
try:
self.tf_listener.waitForTransform(self.odom_frame, '/base_footprint', rospy.Time(), rospy.Duration(1.0))
self.base_frame = '/base_footprint'
except (tf.Exception, tf.ConnectivityException, tf.LookupException):
try:
self.tf_listener.waitForTransform(self.odom_frame, '/base_link', rospy.Time(), rospy.Duration(1.0))
self.base_frame = '/base_link'
except (tf.Exception, tf.ConnectivityException, tf.LookupException):
rospy.loginfo("Cannot find transform between /odom and /base_link or /base_footprint")
rospy.signal_shutdown("tf Exception")
position = Point()
for i in range(4):
move_cmd = Twist()
move_cmd.linear.x = linear_speed
(position, rotation) = self.get_odom()
x_start = position.x
y_start = position.y
distance = 0
while distance < goal_distance and not rospy.is_shutdown():
self.cmd_vel.publish(move_cmd)
r.sleep()
(position, rotation) = self.get_odom()
distance = sqrt(pow((position.x - x_start), 2) +
pow((position.y - y_start), 2))
move_cmd = Twist()
self.cmd_vel.publish(move_cmd)
rospy.sleep(1.0)
move_cmd.angular.z = angular_speed
last_angle = rotation
turn_angle = 0
while abs(turn_angle + angular_tolerance) < abs(goal_angle) and not rospy.is_shutdown():
self.cmd_vel.publish(move_cmd)
r.sleep()
(position, rotation) = self.get_odom()
delta_angle = normalize_angle(rotation - last_angle)
turn_angle += delta_angle
last_angle = rotation
move_cmd = Twist()
self.cmd_vel.publish(move_cmd)
rospy.sleep(1.0)
self.cmd_vel.publish(Twist())
def get_odom(self):
try:
(trans, rot) = self.tf_listener.lookupTransform(self.odom_frame, self.base_frame, rospy.Time(0))
except (tf.Exception, tf.ConnectivityException, tf.LookupException):
rospy.loginfo("TF Exception")
return
return (Point(*trans), quat_to_angle(Quaternion(*rot)))
def shutdown(self):
rospy.loginfo("Stopping the robot...")
self.cmd_vel.publish(Twist())
rospy.sleep(1)
if __name__ == '__main__':
try:
NavSquare()
except rospy.ROSInterruptException:
rospy.loginfo("Navigation terminated.")
4 转换后的C++代码
nav_square.cpp
#include <math.h>
#include <signal.h>
#include "ros/ros.h"
#include "geometry_msgs/Twist.h"
#include "geometry_msgs/Point.h"
#include "geometry_msgs/Quaternion.h"
#include "tf/transform_listener.h"
ros::Publisher cmd_vel_pub;
void NodeShutdown(int sig)
{
ROS_INFO("node \"nav_square\" shutting down!");
cmd_vel_pub.publish(geometry_msgs::Twist());
sleep(1);
ros::shutdown();
exit(sig);
}
bool get_odom(const tf::TransformListener &listener,
const std::string &target_frame,
const std::string &source_frame,
tf::StampedTransform &transform)
{
try
{
listener.lookupTransform(target_frame, source_frame, ros::Time(0), transform);
}
catch(...)
{
ROS_ERROR("TF Exception");
return false;
}
return true;
}
int main(int argc, char **argv)
{
ros::init(argc, argv, "nav_square", ros::init_options::NoSigintHandler);
ros::NodeHandle node;
signal(SIGINT, NodeShutdown);
cmd_vel_pub = node.advertise<geometry_msgs::Twist>("/cmd_vel", 5);
int rate = 20;
ros::Rate loop_rate(rate);
double goal_distance;
double goal_angle;
double linear_speed;
double angular_speed;
double angular_tolerance;
ros::param::param<double>("~goal_distance", goal_distance, 1.0 );
ros::param::param<double>("~goal_angle", goal_angle, M_PI_2);
ros::param::param<double>("~linear_speed", linear_speed, 0.2 );
ros::param::param<double>("~angular_speed", angular_speed, 0.2 );
ros::param::param<double>("~angular_tolerance", angular_tolerance, M_PI/180.0);
std::string base_frame;
ros::param::param<std::string>("~base_frame", base_frame, "/base_footprint");
std::string odom_frame;
ros::param::param<std::string>("~odom_frame", odom_frame, "/odom");
tf::TransformListener tf_listener;
sleep(2);
geometry_msgs::Point position;
for (int i = 0; i < 4; ++i)
{
geometry_msgs::Twist move_cmd;
move_cmd.linear.x = linear_speed;
tf::StampedTransform transform;
get_odom(tf_listener, odom_frame, base_frame, transform);
double x_start = transform.getOrigin().x();
double y_start = transform.getOrigin().y();
double distance = 0;
while (distance < goal_distance && node.ok())
{
cmd_vel_pub.publish(move_cmd);
loop_rate.sleep();
get_odom(tf_listener, odom_frame, base_frame, transform);
position.x = transform.getOrigin().x();
position.y = transform.getOrigin().y();
distance = sqrt(pow((position.x - x_start), 2) +
pow((position.y - y_start), 2));
}
move_cmd.linear.x = 0;
cmd_vel_pub.publish(move_cmd);
loop_rate.sleep();
move_cmd.angular.z = angular_speed;
double last_angle = fabs(tf::getYaw(transform.getRotation()));
double turn_angle = 0;
while(fabs(turn_angle + angular_tolerance) < fabs(goal_angle) && node.ok())
{
cmd_vel_pub.publish(move_cmd);
loop_rate.sleep();
get_odom(tf_listener, odom_frame, base_frame, transform);
double current_angle = fabs(tf::getYaw(transform.getRotation()));
double delta_angle = fabs(current_angle - last_angle);
turn_angle += delta_angle;
last_angle = current_angle;
}
move_cmd.angular.z = 0;
cmd_vel_pub.publish(move_cmd);
loop_rate.sleep();
cmd_vel_pub.publish(geometry_msgs::Twist());
}
return 0;
}
在编译前,还需要在CMakeLists.txt文件中加入以下内容:
add_executable(nav_square src/nav_square.cpp)
target_link_libraries(nav_square ${catkin_LIBRARIES})
|