-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathwidowx_arm_testing.cpp
196 lines (179 loc) · 6.66 KB
/
widowx_arm_testing.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
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
#include "ros/ros.h"
#include "std_msgs/Float64.h"
#include "sensor_msgs/JointState.h"
#include "arbotix_msgs/Relax.h"
/**
* Basic testing for the WidowX arm.
* Copyright (C) 2015 Ana Cruz-Martín ([email protected])
*
* DISCLAIMER: This is a work-in-progress test code, not finished yet.
*
* This code must be integrated into a ros package, and then called with rosrun,
* while the widowx arm software by Robotnik is running.
* https://github.com/RobotnikAutomation/widowx_arm
*
* For videos and further information
* http://jafma.net/ana/theweekendarchaeologist/?post=564
*
* TO DO:
* - Clean and organize code
* - Create a proper launch file
* - rviz integration
*/
void jointsCallback(const sensor_msgs::JointState::ConstPtr& jointsmsg)
{
ROS_INFO("JOINTS POSITIONS[1: %f] [2: %f] [3: %f] [4: %f] [5: %f] [6: %f]\n", jointsmsg->position[1], jointsmsg->position[2], jointsmsg->position[3], jointsmsg->position[4], jointsmsg->position[5], jointsmsg->position[6]);
ROS_INFO("\nJOINTS VELOCITIES[1: %f] [2: %f] [3: %f] [4: %f] [5: %f] [6: %f]\n", jointsmsg->velocity[1], jointsmsg->velocity[2], jointsmsg->velocity[3], jointsmsg->velocity[4], jointsmsg->velocity[5], jointsmsg->velocity[6]);
}
int main(int argc, char **argv)
{
ros::init(argc, argv , "widowx_arm_testing");
ros::NodeHandle n;
// Topics of the joints.
ros::Publisher joint1 = n.advertise<std_msgs::Float64>("/arm_1_joint/command", 1000);
ros::Publisher joint2 = n.advertise<std_msgs::Float64>("/arm_2_joint/command", 1000);
ros::Publisher joint3 = n.advertise<std_msgs::Float64>("/arm_3_joint/command", 1000);
ros::Publisher joint4 = n.advertise<std_msgs::Float64>("/arm_4_joint/command", 1000);
ros::Publisher joint5 = n.advertise<std_msgs::Float64>("/arm_5_joint/command", 1000);
ros::Publisher gripper = n.advertise<std_msgs::Float64>("/gripper_1_joint/command", 1000);
ros::Rate loop_rate(10);
ros::Subscriber joints = n.subscribe("/joint_states", 1000, jointsCallback);
// Relax services of the joints
ros::ServiceClient client_service_joint1_relax = n.serviceClient<arbotix_msgs::Relax>("/arm_1_joint/relax");
ros::ServiceClient client_service_joint2_relax = n.serviceClient<arbotix_msgs::Relax>("/arm_2_joint/relax");
ros::ServiceClient client_service_joint3_relax = n.serviceClient<arbotix_msgs::Relax>("/arm_3_joint/relax");
ros::ServiceClient client_service_joint4_relax = n.serviceClient<arbotix_msgs::Relax>("/arm_4_joint/relax");
ros::ServiceClient client_service_joint5_relax = n.serviceClient<arbotix_msgs::Relax>("/arm_5_joint/relax");
ros::ServiceClient client_service_gripper_relax = n.serviceClient<arbotix_msgs::Relax>("/gripper_1_joint/relax");
arbotix_msgs::Relax srv_joint1_relax;
arbotix_msgs::Relax srv_joint2_relax;
arbotix_msgs::Relax srv_joint3_relax;
arbotix_msgs::Relax srv_joint4_relax;
arbotix_msgs::Relax srv_joint5_relax;
arbotix_msgs::Relax srv_gripper_relax;
/**
* Main code.
*/
std_msgs::Float64 radszero, radspos, radsneg, gripperzero, gripperpos;
radszero.data = 0;
radspos.data = 0.25;
radsneg.data = -0.25;
gripperzero.data = 0;
gripperpos.data = 2.0;
int count = 0;
while (ros::ok() && count<=10)
{
if (count == 0)
{
// "Homing" (all joints to zero)
ROS_INFO("3 SECONDS TO HOME\n");
ros::Duration(3).sleep();
joint2.publish(radszero);
joint3.publish(radszero);
joint4.publish(radszero);
joint5.publish(radszero);
joint1.publish(radszero);
gripper.publish(gripperzero);
ros::Duration(2).sleep();
gripper.publish(gripperpos);
ros::Duration(2).sleep();
gripper.publish(gripperzero);
ros::Duration(2).sleep();
// Once the robot is "homed", we check that all joints move in both directions
ROS_INFO("3 SECONDS TO CHECK DIRECTIONS\n");
ros::Duration(3).sleep();
joint1.publish(radspos); // Move joint 1 with positive and negative values
ros::Duration(2).sleep();
joint1.publish(radsneg);
ros::Duration(2).sleep();
joint1.publish(radszero);
ros::Duration(3).sleep();
joint2.publish(radspos); // Move joint 2 with positive and negative values
ros::Duration(2).sleep();
joint2.publish(radsneg);
ros::Duration(2).sleep();
joint2.publish(radszero);
ros::Duration(3).sleep();
joint3.publish(radspos); // Move joint 3 with positive and negative values
ros::Duration(2).sleep();
joint3.publish(radsneg);
ros::Duration(2).sleep();
joint3.publish(radszero);
ros::Duration(3).sleep();
joint4.publish(radspos); // Move joint 4 with positive and negative values
ros::Duration(2).sleep();
joint4.publish(radsneg);
ros::Duration(2).sleep();
joint4.publish(radszero);
ros::Duration(3).sleep();
joint5.publish(radspos); // Move joint 5 with positive and negative values
ros::Duration(2).sleep();
joint5.publish(radsneg);
ros::Duration(2).sleep();
joint5.publish(radszero);
ros::Duration(3).sleep();
// Finally, we relax every joint in the proper order. Look out: the arm rests completely, collitions may happen!!
ROS_INFO("3 SECONDS TO RELAX\n");
ros::Duration(3).sleep();
if (client_service_gripper_relax.call(srv_gripper_relax))
{
ROS_INFO("Gripper relaxed");
}
else
{
ROS_ERROR("Gripper relax failed");
}
ros::Duration(1).sleep();
if (client_service_joint5_relax.call(srv_joint5_relax))
{
ROS_INFO("Joint 5 relaxed");
}
else
{
ROS_ERROR("Joint 5 relax failed");
}
ros::Duration(1).sleep();
if (client_service_joint4_relax.call(srv_joint4_relax))
{
ROS_INFO("Joint 4 relaxed");
}
else
{
ROS_ERROR("Joint 4 relax failed");
}
ros::Duration(1).sleep();
if (client_service_joint3_relax.call(srv_joint3_relax))
{
ROS_INFO("Joint 3 relaxed");
}
else
{
ROS_ERROR("Joint 3 relax failed");
}
ros::Duration(1).sleep();
if (client_service_joint2_relax.call(srv_joint2_relax))
{
ROS_INFO("Joint 2 relaxed");
}
else
{
ROS_ERROR("Joint 2 relax failed");
}
ros::Duration(1).sleep();
if (client_service_joint1_relax.call(srv_joint1_relax))
{
ROS_INFO("Joint 1 relaxed");
}
else
{
ROS_ERROR("Joint 1 relax failed");
}
ros::Duration(1).sleep();
}
ROS_INFO("Count: %d\n",count);
count++;
ros::spinOnce();
loop_rate.sleep();
}
return 0;
}