Tetrapod Project
velocity_step_response_test.cpp
Go to the documentation of this file.
1 #include "ros/ros.h"
2 #include <ros/console.h>
3 
5 
6 int main(int argc, char **argv)
7 {
8  double PUBLISH_FREQUENCY = 200.0;
9 
10  double STEP_TIME = 0.2;
11 
12  double APPLY_VELOCITY_DURATION = 1.0;
13 
14  double SETPOINT_VELOCITY = 360.0*M_PI/180.0; // rad/s
15 
16  SingleMotorController controller(PUBLISH_FREQUENCY);
17 
18  controller.initROS();
19 
20  controller.initializeMotor();
21 
22  ros::Rate check_for_messages_rate(1);
23 
24  ros::Rate send_command_rate(PUBLISH_FREQUENCY);
25 
26  // Make sure we have received initial states from the motor
27  while(!controller.initialStateReceived())
28  {
29  controller.checkForNewMessages();
30  ROS_INFO("Waiting for state");
31  controller.printAll();
32  check_for_messages_rate.sleep();
33  }
34 
35  // Wait for the start signal
36  while(!controller.readyToProceed())
37  {
38  controller.checkForNewMessages();
39  ROS_INFO("Waiting for ready to proceed");
40  controller.printAll();
41  check_for_messages_rate.sleep();
42  }
43 
44  // Apply zero torque for a fixed duration and log the states
45  for(int i = 0; i < STEP_TIME*PUBLISH_FREQUENCY; i++)
46  {
47  controller.checkForNewMessages();
48  //controller.setVelocityDirectly(0.0);
49  controller.writeToLog();
50  ROS_INFO("Start");
51  controller.printAll();
52  send_command_rate.sleep();
53  }
54 
55  // Apply the desired step torque for a fixed duration and log the states
56  for(int i = 0; i < APPLY_VELOCITY_DURATION*PUBLISH_FREQUENCY; i++)
57  {
58  controller.checkForNewMessages();
59  controller.setVelocityDirectly(SETPOINT_VELOCITY);
60  controller.writeToLog();
61  ROS_INFO("HIGH");
62  controller.printAll();
63  send_command_rate.sleep();
64  }
65 
66  // Apply zero torque until the program shuts down
67  for (int i = 0; i < 100; i++)
68  {
69  controller.checkForNewMessages();
70  controller.setVelocityDirectly(0.0);
71  ROS_INFO("FINISHED");
72  controller.printAll();
73  send_command_rate.sleep();
74  }
75 
76  return 0;
77 }
78 
void setVelocityDirectly(double _joint_vel)
void initializeMotor(double _k_p_pos, double _k_d_pos, double _k_p_vel, double _k_i_vel, double _k_p_torque, double _k_i_torque)
int main(int argc, char **argv)