|
@@ -6,15 +6,14 @@
|
|
|
*/
|
|
|
#include <infrared_demo.h>
|
|
|
|
|
|
-Infrared_Demo::Infrared_Demo(){
|
|
|
-
|
|
|
+Infrared_Demo::Infrared_Demo()
|
|
|
+{
|
|
|
//从参数服务器中取“center_dist”数据
|
|
|
ros::param::param<float>("~center_dist", center_dist, 0.2);
|
|
|
-
|
|
|
//订阅红外数据
|
|
|
_infrared_sub = nh.subscribe<ros_arduino_msgs::InfraredSensors>("/mobilebase_arduino/sensor/GP2Y0A41", 1, &Infrared_Demo::infrared_callback, this);
|
|
|
//注册小车速度发布者
|
|
|
- _cmd_vel_pub = nh.advertise<geometry_msgs::Twist>("/cmd_vel", 1);
|
|
|
+ _cmd_vel_pub = nh.advertise<geometry_msgs::Twist>("/cmd_vel", 2);
|
|
|
}
|
|
|
|
|
|
Infrared_Demo::~Infrared_Demo(){
|
|
@@ -23,31 +22,32 @@ Infrared_Demo::~Infrared_Demo(){
|
|
|
/**
|
|
|
* @description: 订阅红外数据回调函数
|
|
|
*/
|
|
|
-void Infrared_Demo::infrared_callback(const ros_arduino_msgs::InfraredSensors::ConstPtr &data){
|
|
|
-
|
|
|
+void Infrared_Demo::infrared_callback(const ros_arduino_msgs::InfraredSensors::ConstPtr &data)
|
|
|
+{
|
|
|
//获取前红外信息
|
|
|
float front_dist = data->front_dist;
|
|
|
-
|
|
|
//根据前红外反馈的距离来控制小车运动,离小车较远时小车前进,离小车较近时小车后退
|
|
|
- if(front_dist > 0.28){
|
|
|
+ if(front_dist > 0.28)
|
|
|
+ {
|
|
|
_twist.linear.x = 0;
|
|
|
_cmd_vel_pub.publish(_twist);
|
|
|
- }else{
|
|
|
+ }
|
|
|
+ else
|
|
|
+ {
|
|
|
float err_dist = front_dist - center_dist;
|
|
|
- _twist.linear.x = 0.74 * err_dist * 2;
|
|
|
- if(abs(_twist.linear.x) < 0.015){
|
|
|
+ _twist.linear.x = 3.0 * err_dist;
|
|
|
+ if(abs(_twist.linear.x) < 0.1)
|
|
|
+ {
|
|
|
_twist.linear.x = 0;
|
|
|
}
|
|
|
_cmd_vel_pub.publish(_twist);
|
|
|
}
|
|
|
}
|
|
|
|
|
|
-int main(int argc, char **argv){
|
|
|
-
|
|
|
- //初始化节点
|
|
|
+int main(int argc, char **argv)
|
|
|
+{
|
|
|
ros::init(argc, argv, "infrared_demo_node");
|
|
|
//根据Infrafed_Demo声明对象,调用构造函数
|
|
|
Infrared_Demo infrared_demo;
|
|
|
- //使ROS中回调函数生效
|
|
|
ros::spin();
|
|
|
-}
|
|
|
+}
|