Skip to content

Commit 7d07472

Browse files
committed
cleaned up arm_hardware_interface to an extent
1 parent 3853491 commit 7d07472

File tree

4 files changed

+197
-243
lines changed

4 files changed

+197
-243
lines changed

src/arm_hardware_interface/include/ArmSerialInterface.h

Lines changed: 21 additions & 135 deletions
Original file line numberDiff line numberDiff line change
@@ -25,23 +25,12 @@
2525
#define AXIS_5_DIR 1
2626
#define AXIS_6_DIR 1
2727

28-
29-
30-
31-
3228
using std::string;
3329

34-
35-
3630
class ArmSerial : public rclcpp::Node {
3731
public:
3832
ArmSerial();
39-
void recieveMsg();
40-
void sendHomeCmd(int target_axis);
41-
void sendCommCmd(int target_state);
42-
void sendMsg(std::string outMsg);
43-
void parseArmAngleUart(std::string msg);
44-
void parseLimitSwitchTest(std::string msg);
33+
4534
// float firm
4635

4736
rover_msgs::msg::ArmCommand current_arm_status;
@@ -56,17 +45,12 @@ class ArmSerial : public rclcpp::Node {
5645

5746
private:
5847

59-
float degToRad(float deg);
60-
float firmToMoveitOffsetPos(float deg, int axis);
61-
float firmToMoveitOffsetVel(float deg, int axis);
62-
63-
64-
unsigned long baud = 115200;//19200;
48+
unsigned long baud = 115200;//19200;
6549
string port = "/dev/serial/by-id/usb-ZEPHYR_UBC_ROVER_Arm_500100C6224069D7-if00";
6650

6751
serial::Serial teensy;
6852
serial::Timeout timeout_uart = serial::Timeout::simpleTimeout(1000); // E.g., 1000 ms or 1 second
69-
53+
7054

7155
struct Axis{
7256
float curr_pos;
@@ -77,57 +61,21 @@ class ArmSerial : public rclcpp::Node {
7761
int dir;
7862
};
7963

80-
void CommandCallback(const rover_msgs::msg::ArmCommand::SharedPtr msg);
81-
8264
Axis axes[NUM_JOINTS];
8365
// Axis axis_EE;
8466

85-
86-
void send_position_command(float pos[NUM_JOINTS]) {
87-
88-
char tx_msg[TX_UART_BUFF];
89-
90-
sprintf(tx_msg, "$P(%0.2f, %0.2f, %0.2f, %0.2f, %0.2f, %0.2f, %0.2f)\n", pos[0], pos[1], pos[2], pos[3], pos[4], pos[5], pos[6]);
91-
92-
sendMsg(tx_msg);
93-
RCLCPP_INFO(this->get_logger(), "Positions Sent %s", tx_msg);
94-
95-
}
96-
void send_velocity_command(float vel[NUM_JOINTS]) {
97-
98-
char tx_msg[TX_UART_BUFF];
99-
100-
sprintf(tx_msg, "$V(%0.2f, %0.2f, %0.2f, %0.2f, %0.2f, %0.2f, %0.2f)\n", vel[0], vel[1], vel[2], vel[3], vel[4], vel[5], vel[6]);
101-
for(int i = 0; i < NUM_JOINTS; i++){
102-
current_velocity[i] = vel[i];
103-
}
104-
105-
106-
sendMsg(tx_msg);
107-
// RCLCPP_INFO(this->get_logger(), "Velocities Sent %s", tx_msg);
108-
109-
}
110-
void send_test_limits_command(){
111-
char tx_msg[TX_UART_BUFF];
112-
sprintf(tx_msg, "$t()\n");
113-
sendMsg(tx_msg);
114-
RCLCPP_INFO(this->get_logger(), "Test limits Sent %s", tx_msg);
115-
116-
}
117-
118-
void send_gear_command(int gear){
119-
120-
}
121-
float target_position[NUM_JOINTS];
122-
float target_velocities[NUM_JOINTS];
67+
float target_position[NUM_JOINTS];
68+
float target_velocities[NUM_JOINTS];
12369

12470
int homed = 0;
12571
bool homing = false;
12672
float EE = 0;
12773
volatile float current_velocity[NUM_JOINTS] = {00.00, 00.00, 00.00, 00.00, 00.00, 00.00, 00.00};
12874
volatile float current_position[NUM_JOINTS] = {00.00, 00.00, 00.00, 00.00, 00.00, 00.00, 00.00};
12975
volatile int current_limit_switches[NUM_JOINTS] = {-1, -1, -1, -1, -1, -1, -1};
76+
13077
rclcpp::Subscription<rover_msgs::msg::ArmCommand>::SharedPtr command_subscriber;
78+
void CommandCallback(const rover_msgs::msg::ArmCommand::SharedPtr msg);
13179

13280
rclcpp::Publisher<sensor_msgs::msg::JointState>::SharedPtr joint_state_publisher_;
13381

@@ -136,84 +84,22 @@ class ArmSerial : public rclcpp::Node {
13684

13785
rclcpp::TimerBase::SharedPtr timer_;
13886

139-
140-
141-
// void joy_callback(const sensor_msgs::msg::Joy::SharedPtr msg){
142-
// //RCLCPP_INFO(this->get_logger(), "Joy Recieved");
143-
// if(!homing){
144-
// int home_button = msg->buttons[2];
145-
146-
// if(!home_button && homed){
147-
// target_position[0] = msg->axes[0]*10;
148-
// target_position[1] = msg->axes[1]*10;
149-
// target_position[2] = msg->axes[3]*10;
150-
// target_position[3] = msg->axes[4]*10;
151-
// target_position[4] = msg->axes[0]*10;
152-
// target_position[5] = msg->axes[0]*10;
153-
// send_position_command(target_position);
154-
155-
// }else{
156-
// homing = true;
157-
// sendCommCmd();
158-
// sendHomeCmd();
159-
// }
160-
// }else{
161-
162-
// }
163-
164-
// }
16587
std::thread serialRxThread;
16688

167-
168-
169-
void serial_rx(){
170-
//rclcpp::Rate loop_rate(50);
171-
std::string next_char = "";
172-
std::string buffer = "";
173-
int timeoutCounter = 0;
174-
//zephyrComm.teensy.flushInput();
175-
if (teensy.available() > 0){
176-
// ROS_WARN("Reading");
177-
178-
//timeoutCounter ++;
179-
// next_char = teensy.read();
180-
buffer = teensy.read(RX_UART_BUFF);
181-
RCLCPP_WARN(this->get_logger(), "%s", buffer.c_str());
182-
// if(next_char == "\n" || next_char == "\r" || next_char == "\0"){
183-
// timeoutCounter = RX_UART_BUFF;
184-
// }
185-
if (buffer.size() > 0){
186-
if(buffer.find("Arm Ready") != std::string::npos){
187-
homed = true;
188-
homing = false;
189-
// fresh_rx_angle = true;
190-
}else if(buffer.find("my_angleP") != std::string::npos){
191-
parseArmAngleUart(buffer);
192-
}else if(buffer.find("Limit Switch")){
193-
parseLimitSwitchTest(buffer);
194-
}
195-
196-
197-
}
198-
199-
200-
201-
// if (buffer.size() > 0){
202-
// if(buffer.find("Arm Ready") != std::string::npos){
203-
// homed = true;
204-
// // fresh_rx_angle = true;
205-
// }else if(buffer.find("my_angleP") != std::string::npos){
206-
// parseArmAngleUart(buffer);
207-
// }
208-
209-
210-
// }
211-
//sleep(1);
212-
}
213-
}
214-
215-
};
216-
89+
void serial_rx(); //? should be static inline?
90+
float degToRad(float deg);
91+
float firmToMoveitOffsetPos(float deg, int axis);
92+
float firmToMoveitOffsetVel(float deg, int axis);
93+
void send_position_command(float pos[NUM_JOINTS]);
94+
void send_velocity_command(float vel[NUM_JOINTS]);
95+
void send_test_limits_command();
96+
void sendHomeCmd(int target_axis);
97+
void sendCommCmd(int target_state);
98+
void sendMsg(std::string outMsg);
99+
void parseArmAngleUart(std::string msg);
100+
void parseLimitSwitchTest(std::string msg);
101+
};
102+
217103

218104

219105

0 commit comments

Comments
 (0)