-
Notifications
You must be signed in to change notification settings - Fork 8
/
velodyne_plugin.cc
171 lines (150 loc) · 6.39 KB
/
velodyne_plugin.cc
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
#include <thread>
#include <deque>
#include <cmath>
#include <gazebo/common/common.hh>
#include <gazebo/gazebo.hh>
#include <gazebo/gazebo_config.h>
#include <gazebo/physics/physics.hh>
#include <gazebo/physics/Joint.hh>
#include <gazebo/msgs/msgs.hh>
#include <gazebo/transport/Node.hh>
#include <gazebo/transport/transport.hh>
#include <gazebo/msgs/msgs.hh>
#include <ignition/math/Angle.hh>
#include <ros/ros.h>
#include <ros/callback_queue.h>
#include <ros/subscribe_options.h>
#include <tf2/utils.h>
#include <tf2_ros/transform_broadcaster.h>
#include <tf2_ros/transform_listener.h>
#include <geometry_msgs/TransformStamped.h>
#include <std_msgs/Float32.h>
#include <sensor_msgs/LaserScan.h>
namespace gazebo
{
class VelodynePlugin : public ModelPlugin
{
public: VelodynePlugin() {}
~VelodynePlugin() {
delete mTfBr;
}
/*
* Load - 在插入本插件的时候, Gazebo就会调用该函数, 进行一些初始化的操作.
*
* @model: 指向与本插件相关联的模型的指针
* @sdf: 指向本插件SDF元素的指针
*/
public: virtual void Load(physics::ModelPtr model, sdf::ElementPtr sdf)
{
if (model->GetJointCount() == 0) {
std::cerr << "没有正确装载velodyne模型\n";
return;
}
this->mModel = model;
this->mJoint = model->GetJoints()[0];
this->mPid = common::PID(0.1, 0, 0);
this->mModel->GetJointController()->SetVelocityPID(this->mJoint->GetScopedName(), this->mPid);
// ROS 配置
if (!ros::isInitialized()) {
int argc = 0;
char **argv = NULL;
ros::init(argc, argv, "gazebo_demos", ros::init_options::NoSigintHandler);
}
this->mRosNode.reset(new ros::NodeHandle("gazebo_demos"));
ros::SubscribeOptions so = ros::SubscribeOptions::create<std_msgs::Float32>(
"/" + this->mModel->GetName() + "/vel_cmd",
1,
boost::bind(&VelodynePlugin::OnVelCmdMsgFromROS, this, _1),
ros::VoidPtr(), &this->mRosQueue);
this->mRosSub = this->mRosNode->subscribe(so);
// Laser Scan
this->mGazeboNode = gazebo::transport::NodePtr(new gazebo::transport::Node());
this->mGazeboNode->Init();
mLaserScanSub = this->mGazeboNode->Subscribe("~/my_velodyne/velodyne_hdl-32/top/sensor/scan", &VelodynePlugin::OnLaserScanMsg, this);
this->mRosPub = this->mRosNode->advertise<sensor_msgs::LaserScan>("/laserscan", 10);
this->mTfBr = new tf2_ros::TransformBroadcaster();
this->mRosQueueThread = std::thread(std::bind(&VelodynePlugin::RosQueueThread, this));
}
/*
* SetVelocity - 设定Velodyne的转速
*
* @vel: 激光雷达的扫描转速, rad/s
*/
public: void SetVelocity(const double &vel)
{
this->mModel->GetJointController()->SetVelocityTarget(this->mJoint->GetScopedName(), vel);
}
/*
* OnVelCmdMsgFromROS - 接收到来自ROS系统的调速消息的回调函数
*
* @msg: 调速消息
*/
private: void OnVelCmdMsgFromROS(const std_msgs::Float32ConstPtr & msg)
{
this->SetVelocity(msg->data);
}
/*
* RosQueueThread - 处理ROS消息队列的线程
*/
private: void RosQueueThread()
{
static const double timeout = 0.01;
while (this->mRosNode->ok()) {
while (!this->mLaserScanQueue.empty()) {
sensor_msgs::LaserScan &laser_msg = mLaserScanQueue.front();
this->mRosPub.publish(laser_msg);
mLaserScanQueue.pop_front();
}
this->mRosQueue.callAvailable(ros::WallDuration(timeout));
}
}
private: void OnLaserScanMsg(ConstLaserScanStampedPtr & msg)
{
sensor_msgs::LaserScan laser_msg;
laser_msg.header.stamp = ros::Time(msg->time().sec(), msg->time().nsec());
laser_msg.header.frame_id = "top";
laser_msg.angle_min = msg->scan().angle_min();
laser_msg.angle_max = msg->scan().angle_max();
laser_msg.angle_increment = msg->scan().angle_step();
laser_msg.time_increment = 0; // instantaneous simulator scan
laser_msg.scan_time = 0; // not sure whether this is correct
laser_msg.range_min = msg->scan().range_min();
laser_msg.range_max = msg->scan().range_max();
laser_msg.ranges.resize(msg->scan().ranges_size());
std::copy(msg->scan().ranges().begin(), msg->scan().ranges().end(), laser_msg.ranges.begin());
laser_msg.intensities.resize(msg->scan().intensities_size());
std::copy(msg->scan().intensities().begin(), msg->scan().intensities().end(), laser_msg.intensities.begin());
mLaserScanQueue.push_back(laser_msg);
gazebo::common::Time now = this->mModel->GetWorld()->SimTime();
double position = mJoint->Position();
double c = std::cos(position);
double s = std::sin(position);
tf2::Matrix3x3 rot(c, 0, s,
s, 0, -c,
0, 1, 0);
tf2::Vector3 ori(0, 0, 0);
tf2::Transform trans(rot, ori);
geometry_msgs::TransformStamped stampedTrans;
stampedTrans.transform = tf2::toMsg(trans);
stampedTrans.header.frame_id = "base";
stampedTrans.header.stamp = ros::Time(now.sec, now.nsec);
stampedTrans.child_frame_id = "top";
mTfBr->sendTransform(stampedTrans);
}
private:
std::unique_ptr<ros::NodeHandle> mRosNode;
ros::Subscriber mRosSub;
ros::Publisher mRosPub;
ros::CallbackQueue mRosQueue;
tf2_ros::TransformBroadcaster *mTfBr;
std::thread mRosQueueThread;
physics::ModelPtr mModel;
physics::JointPtr mJoint;
common::PID mPid;
gazebo::transport::NodePtr mGazeboNode;
gazebo::transport::SubscriberPtr mLaserScanSub;
std::deque<sensor_msgs::LaserScan> mLaserScanQueue;
};
// 向Gazebo注册本插件
GZ_REGISTER_MODEL_PLUGIN(VelodynePlugin)
}