
This code is for controlling DC motors with a Sabertooth 2x25 V2 motor driver produced by Dimension Engineering. You can drive DC motors via serial communication or rosserial.
Dependencies: ros_lib_kinetic QEI
Revision 6:ad25826cc7e0, committed 2018-03-28
- Comitter:
- jkoba0512
- Date:
- Wed Mar 28 00:34:50 2018 +0000
- Parent:
- 5:5b7b5542434c
- Commit message:
- PI gains are obtained from ROS parameter server
Changed in this revision
main.cpp | Show annotated file Show diff for this revision Revisions of this file |
--- a/main.cpp Fri Mar 23 01:58:36 2018 +0000 +++ b/main.cpp Wed Mar 28 00:34:50 2018 +0000 @@ -140,11 +140,11 @@ } ros::Subscriber<std_msgs::Int32> desired_enc_pulse_count_rate_ch1_sub("desired_enc_pulse_count_rate_ch1", &message_desired_enc_pulse_count_rate_ch1); +// PI gains obtained from ROS parameter server +float Kp_v; +float Ki_v; + void feedback_control() { - // PI gains - const float Kp_v = 0.1; - const float Ki_v = 0.1; - // encoder pulse count rate error int enc_pulse_count_rate_error[2]; @@ -299,6 +299,10 @@ nh.advertise(desired_enc_pulse_count_rate_ch1_current_pub); nh.subscribe(desired_enc_pulse_count_rate_ch0_sub); nh.subscribe(desired_enc_pulse_count_rate_ch1_sub); + + // obtain PI gains from ROS parameter server + if (!nh.getParam("/dcmotor_control_sabertooth_rosserial/Kp_v", &Kp_v, 1)) Kp_v = 0.0; + if (!nh.getParam("/dcmotor_control_sabertooth_rosserial/Ki_v", &Ki_v, 1)) Ki_v = 0.0; #endif // FEEDBACK_ON #endif // ENCODER_ON #endif // SERIAL_COM_MODE