forked from RoboMaster/RoboRTS-Base
-
Notifications
You must be signed in to change notification settings - Fork 0
/
gimbal.cpp
165 lines (144 loc) · 6.91 KB
/
gimbal.cpp
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
/****************************************************************************
* Copyright (C) 2021 RoboMaster.
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
***************************************************************************/
#include "gimbal.h"
namespace roborts_base{
Gimbal::Gimbal(std::shared_ptr<roborts_sdk::Handle> handle):
Module(handle){
SDK_Init();
ROS_Init();
}
Gimbal::~Gimbal(){
if(heartbeat_thread_.joinable()){
heartbeat_thread_.join();
}
}
void Gimbal::SDK_Init(){
verison_client_ = handle_->CreateClient<roborts_sdk::cmd_version_id,roborts_sdk::cmd_version_id>
(UNIVERSAL_CMD_SET, CMD_REPORT_VERSION,
MANIFOLD2_ADDRESS, GIMBAL_ADDRESS);
roborts_sdk::cmd_version_id version_cmd;
version_cmd.version_id=0;
auto version = std::make_shared<roborts_sdk::cmd_version_id>(version_cmd);
verison_client_->AsyncSendRequest(version,
[](roborts_sdk::Client<roborts_sdk::cmd_version_id,
roborts_sdk::cmd_version_id>::SharedFuture future) {
ROS_INFO("Gimbal Firmware Version: %d.%d.%d.%d",
int(future.get()->version_id>>24&0xFF),
int(future.get()->version_id>>16&0xFF),
int(future.get()->version_id>>8&0xFF),
int(future.get()->version_id&0xFF));
});
handle_->CreateSubscriber<roborts_sdk::cmd_gimbal_info>(GIMBAL_CMD_SET, CMD_PUSH_GIMBAL_INFO,
GIMBAL_ADDRESS, BROADCAST_ADDRESS,
std::bind(&Gimbal::GimbalInfoCallback, this, std::placeholders::_1));
gimbal_angle_pub_ = handle_->CreatePublisher<roborts_sdk::cmd_gimbal_angle>(GIMBAL_CMD_SET, CMD_SET_GIMBAL_ANGLE,
MANIFOLD2_ADDRESS, GIMBAL_ADDRESS);
fric_wheel_pub_ = handle_->CreatePublisher<roborts_sdk::cmd_fric_wheel_speed>(GIMBAL_CMD_SET, CMD_SET_FRIC_WHEEL_SPEED,
MANIFOLD2_ADDRESS, GIMBAL_ADDRESS);
gimbal_shoot_pub_ = handle_->CreatePublisher<roborts_sdk::cmd_shoot_info>(GIMBAL_CMD_SET, CMD_SET_SHOOT_INFO,
MANIFOLD2_ADDRESS, GIMBAL_ADDRESS);
heartbeat_pub_ = handle_->CreatePublisher<roborts_sdk::cmd_heartbeat>(UNIVERSAL_CMD_SET, CMD_HEARTBEAT,
MANIFOLD2_ADDRESS, GIMBAL_ADDRESS);
heartbeat_thread_ = std::thread([this]{
roborts_sdk::cmd_heartbeat heartbeat;
heartbeat.heartbeat=0;
while(ros::ok()){
heartbeat_pub_->Publish(heartbeat);
std::this_thread::sleep_for(std::chrono::milliseconds(300));
}
}
);
}
void Gimbal::ROS_Init(){
//ros subscriber
ros_sub_cmd_gimbal_angle_ = ros_nh_.subscribe("cmd_gimbal_angle", 1, &Gimbal::GimbalAngleCtrlCallback, this);
//ros service
ros_ctrl_fric_wheel_srv_ = ros_nh_.advertiseService("cmd_fric_wheel", &Gimbal::CtrlFricWheelService, this);
ros_ctrl_shoot_srv_ = ros_nh_.advertiseService("cmd_shoot", &Gimbal::CtrlShootService, this);
//ros_message_init
gimbal_tf_.header.frame_id = "base_link";
gimbal_tf_.child_frame_id = "gimbal";
}
void Gimbal::GimbalInfoCallback(const std::shared_ptr<roborts_sdk::cmd_gimbal_info> gimbal_info){
ros::Time current_time = ros::Time::now();
geometry_msgs::Quaternion q = tf::createQuaternionMsgFromRollPitchYaw(0.0,
gimbal_info->pitch_ecd_angle / 1800.0 * M_PI,
gimbal_info->yaw_ecd_angle / 1800.0 * M_PI);
gimbal_tf_.header.stamp = current_time;
gimbal_tf_.transform.rotation = q;
gimbal_tf_.transform.translation.x = 0;
gimbal_tf_.transform.translation.y = 0;
gimbal_tf_.transform.translation.z = 0.15;
tf_broadcaster_.sendTransform(gimbal_tf_);
}
void Gimbal::GimbalAngleCtrlCallback(const roborts_msgs::GimbalAngle::ConstPtr &msg){
roborts_sdk::cmd_gimbal_angle gimbal_angle;
gimbal_angle.ctrl.bit.pitch_mode = msg->pitch_mode;
gimbal_angle.ctrl.bit.yaw_mode = msg->yaw_mode;
gimbal_angle.pitch = msg->pitch_angle*1800/M_PI;
gimbal_angle.yaw = msg->yaw_angle*1800/M_PI;
gimbal_angle_pub_->Publish(gimbal_angle);
}
bool Gimbal::CtrlFricWheelService(roborts_msgs::FricWhl::Request &req,
roborts_msgs::FricWhl::Response &res){
roborts_sdk::cmd_fric_wheel_speed fric_speed;
if(req.open){
fric_speed.left = 1240;
fric_speed.right = 1240;
} else{
fric_speed.left = 1000;
fric_speed.right = 1000;
}
fric_wheel_pub_->Publish(fric_speed);
res.received = true;
return true;
}
bool Gimbal::CtrlShootService(roborts_msgs::ShootCmd::Request &req,
roborts_msgs::ShootCmd::Response &res){
roborts_sdk::cmd_shoot_info gimbal_shoot;
uint16_t default_freq = 1500;
switch(static_cast<roborts_sdk::shoot_cmd_e>(req.mode)){
case roborts_sdk::SHOOT_STOP:
gimbal_shoot.shoot_cmd = roborts_sdk::SHOOT_STOP;
gimbal_shoot.shoot_add_num = 0;
gimbal_shoot.shoot_freq = 0;
break;
case roborts_sdk::SHOOT_ONCE:
if(req.number!=0){
gimbal_shoot.shoot_cmd = roborts_sdk::SHOOT_ONCE;
gimbal_shoot.shoot_add_num = req.number;
gimbal_shoot.shoot_freq = default_freq;
}
else{
gimbal_shoot.shoot_cmd = roborts_sdk::SHOOT_ONCE;
gimbal_shoot.shoot_add_num = 1;
gimbal_shoot.shoot_freq = default_freq;
}
break;
case roborts_sdk::SHOOT_CONTINUOUS:
gimbal_shoot.shoot_cmd = roborts_sdk::SHOOT_CONTINUOUS;
gimbal_shoot.shoot_add_num = req.number;
gimbal_shoot.shoot_freq = default_freq;
break;
default:
return false;
}
gimbal_shoot_pub_->Publish(gimbal_shoot);
res.received = true;
return true;
}
}