]> defiant.homedns.org Git - ros_roboint.git/commitdiff
Migration to ros control (diff_drive_controller)
authorErik Andresen <erik@vontaene.de>
Sat, 29 Apr 2017 20:45:29 +0000 (22:45 +0200)
committerErik Andresen <erik@vontaene.de>
Sat, 29 Apr 2017 20:45:29 +0000 (22:45 +0200)
CMakeLists.txt
config/control.yaml [new file with mode: 0644]
explorer_configuration.launch [deleted file]
include/robo_explorer_hardware.h [new file with mode: 0644]
launch/explorer_configuration.launch [new file with mode: 0644]
package.xml
scripts/robo_explorer.py
src/libft_adapter.cpp
src/robo_explorer_hardware.cpp [new file with mode: 0644]
urdf/explorer.urdf

index 820e2583a684b853892fea536596317d167c1198..d5b4f82ce585e0b72c2a57b15b56b0ee0f060372 100644 (file)
@@ -4,7 +4,7 @@ project(roboint)
 ## Find catkin macros and libraries
 ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
 ## is used, also find other catkin packages
-find_package(catkin REQUIRED COMPONENTS roscpp rospy std_msgs message_generation urdf)
+find_package(catkin REQUIRED COMPONENTS roscpp rospy std_msgs message_generation urdf controller_manager)
 
 ## System dependencies are found with CMake's conventions
 # find_package(Boost REQUIRED COMPONENTS system)
@@ -74,6 +74,7 @@ include_directories(include
 ## Declare a cpp executable
 # add_executable(roboint_node src/roboint_node.cpp)
 add_executable(libft_adapter src/libft_adapter.cpp)
+add_executable(robo_explorer_hardware src/robo_explorer_hardware.cpp)
 
 ## Add cmake target dependencies of the executable/library
 ## as an example, message headers may need to be generated before nodes
@@ -84,6 +85,7 @@ add_dependencies(libft_adapter roboint_gencpp)
 #   ${catkin_LIBRARIES}
 # )
 target_link_libraries(libft_adapter ${catkin_LIBRARIES} roboint)
+target_link_libraries(robo_explorer_hardware ${catkin_LIBRARIES})
 
 #############
 ## Install ##
diff --git a/config/control.yaml b/config/control.yaml
new file mode 100644 (file)
index 0000000..990d411
--- /dev/null
@@ -0,0 +1,11 @@
+joint_state_controller:
+  type: "joint_state_controller/JointStateController"
+  publish_rate: 10
+
+diff_drive_controller:
+  type: "diff_drive_controller/DiffDriveController"
+  left_wheel: 'left_wheel_joint'
+  right_wheel: 'right_wheel_joint'
+  pose_covariance_diagonal:  [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 0.03]
+  twist_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 0.03]
+  publish_rate: 10
diff --git a/explorer_configuration.launch b/explorer_configuration.launch
deleted file mode 100644 (file)
index 4bff958..0000000
+++ /dev/null
@@ -1,18 +0,0 @@
-<?xml version="1.0"?>
-<launch>
-       <param name="robot_description" textfile="$(find roboint)/urdf/explorer.urdf" />
-
-       <node pkg="roboint" type="libft_adapter" name="libft_adapter" output="screen">
-       </node>
-
-       <node pkg="roboint" type="robo_explorer.py" name="robo_explorer" output="screen">
-               <!-- Distance between both wheels in meter (18.55cm) -->
-               <param name="wheel_dist" value="0.1855" />
-               <!-- Size of wheel Diameter in meter (5.15cm) * gear ratio (0.5) = 2.575cm -->
-               <param name="wheel_size" value="0.02575" />
-       </node>
-
-       <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />
-
-       <include file="$(find roboint)/launch/move_base.launch"/>
-</launch>
diff --git a/include/robo_explorer_hardware.h b/include/robo_explorer_hardware.h
new file mode 100644 (file)
index 0000000..5c144d5
--- /dev/null
@@ -0,0 +1,103 @@
+#include <hardware_interface/joint_command_interface.h>
+#include <hardware_interface/joint_state_interface.h>
+#include <hardware_interface/robot_hw.h>
+#include "roboint/Inputs.h"
+#include "roboint/Motor.h"
+
+class RoboExplorer : public hardware_interface::RobotHW
+{
+       public:
+               RoboExplorer(ros::NodeHandle nh) { 
+                       this->nh = nh;
+                       pub_motor = nh.advertise<roboint::Motor>("ft/set_motor", 10);
+                       sub_inputs = nh.subscribe("ft/get_inputs", 10, &RoboExplorer::cbInputs, this);
+
+                       // connect and register the joint state interface
+                       hardware_interface::JointStateHandle state_handle_left("left_wheel_joint", &pos[0], &vel[0], &eff[0]);
+                       jnt_state_interface.registerHandle(state_handle_left);
+                       hardware_interface::JointStateHandle state_handle_right("right_wheel_joint", &pos[1], &vel[1], &eff[1]);
+                       jnt_state_interface.registerHandle(state_handle_right);
+                       registerInterface(&jnt_state_interface);
+
+                       // connect and register the joint velocity interface
+                       hardware_interface::JointHandle joint_handle_left(state_handle_left, &cmd[0]);
+                       jnt_velocity_interface.registerHandle(joint_handle_left);
+                       hardware_interface::JointHandle joint_handle_right(state_handle_right, &cmd[1]);
+                       jnt_velocity_interface.registerHandle(joint_handle_right);
+                       registerInterface(&jnt_velocity_interface);
+               }
+
+               // Converts pos_encoder from wheels to wheel angles
+               void read(ros::Duration period) {
+                       static double pos_last[2];
+
+                       pos[0] = pos_encoder[0] * M_PI/8;
+                       pos[1] = pos_encoder[1] * M_PI/8;
+                       vel[0] = (pos[0] - pos_last[0])/period.toSec();
+                       vel[1] = (pos[1] - pos_last[1])/period.toSec();
+                       
+                       std::copy(std::begin(pos), std::end(pos), std::begin(pos_last));
+               }
+
+               // Writes current velocity command to hardware
+               void write() {
+                       double speed_l = 0;
+                       double speed_r = 0;
+                       double wish_speed_left = cmd[0];
+                       double wish_speed_right = cmd[1];
+                       roboint::Motor msg;
+
+                       if (fabs(wish_speed_left) > 0) {
+                               speed_l = 64.3*fabs(wish_speed_left) -1.7;
+                               if (wish_speed_left < 0) speed_l*=-1;
+                       }
+                       if (fabs(wish_speed_right) > 0) {
+                               speed_r = 64.3*fabs(wish_speed_right) -1.7;
+                               if (wish_speed_right < 0) speed_r*=-1;
+                       }
+
+                       // check limits
+                       if (speed_l < -7) speed_l = -7;
+                       else if (speed_l > 7) speed_l = 7;
+                       if (speed_r < -7) speed_r = -7;
+                       else if (speed_r > 7) speed_r = 7;
+
+                       msg.num = 0;
+                       msg.speed = round(speed_l);
+                       pub_motor.publish(msg);
+
+                       msg.num = 1;
+                       msg.speed = round(speed_r);
+                       pub_motor.publish(msg);
+               }
+
+               // Reads current input state and increases pos_encoder on change
+               void cbInputs(const roboint::Inputs::ConstPtr& msg) {
+                       static std::array<uint8_t, 8> input_last;
+
+                       if (msg->input[0] != input_last[0]) { // left input changed
+                               // outputs have direction information
+                               if (msg->output[0] > 0) pos_encoder[0]++;
+                               else if (msg->output[1] > 0) pos_encoder[0]--;
+                       }
+                       if (msg->input[1] != input_last[1]) { // right input changed
+                               // outputs have direction information
+                               if (msg->output[2] > 0) pos_encoder[1]++;
+                               else if (msg->output[3] > 0) pos_encoder[1]--;
+                       }
+
+                       std::copy(std::begin(msg->input), std::end(msg->input), std::begin(input_last));
+               }
+
+       private:
+               hardware_interface::JointStateInterface jnt_state_interface;
+               hardware_interface::VelocityJointInterface jnt_velocity_interface;
+               ros::NodeHandle nh;
+               ros::Publisher pub_motor;
+               ros::Subscriber sub_inputs;
+               double cmd[2];
+               double pos[2];
+               double vel[2];
+               double eff[2];
+               int64_t pos_encoder[2] = {0, 0};
+};
diff --git a/launch/explorer_configuration.launch b/launch/explorer_configuration.launch
new file mode 100644 (file)
index 0000000..354522b
--- /dev/null
@@ -0,0 +1,21 @@
+<?xml version="1.0"?>
+<launch>
+       <param name="robot_description" textfile="$(find roboint)/urdf/explorer.urdf" />
+       <!-- Load controller configurations from YAML file to parameter server -->
+       <rosparam file="$(find roboint)/config/control.yaml" command="load" />
+
+       <node pkg="roboint" type="libft_adapter" name="libft_adapter" output="screen"/>
+       <node pkg="roboint" type="robo_explorer_hardware" name="robo_explorer_hw" output="screen">
+               <remap from="/diff_drive_controller/cmd_vel" to="/cmd_vel" />
+               <remap from="/diff_drive_controller/odom" to="/odom" />
+       </node>
+
+       <node pkg="roboint" type="robo_explorer.py" name="robo_explorer" output="screen"/>
+
+       <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />
+
+       <!-- load the controllers -->
+       <node name="controller_spawner" pkg="controller_manager" type="spawner" output="screen" args="joint_state_controller diff_drive_controller"/>
+
+       <include file="$(find roboint)/launch/move_base.launch"/>
+</launch>
index 7d43954b0e57659b167e97ddebbd45a6630002c3..5918f09aee5b412c0b74d16e01ffdaca2d51e39e 100644 (file)
@@ -53,6 +53,8 @@
   <run_depend>tf</run_depend>
   <build_depend>urdf</build_depend>
   <run_depend>urdf</run_depend>
+  <build_depend>controller_manager</build_depend>
+  <run_depend>controller_manager</run_depend>
 
   <!-- The export tag contains other, unspecified, tags -->
   <export>
index bf3522927532cc94d8223e0fd9628448ccb5344c..83cc48b70b3e40533820de40a8f2c4fcb26c6066 100755 (executable)
@@ -1,12 +1,8 @@
 #!/usr/bin/env python
 import roslib; roslib.load_manifest('roboint')
 import rospy
-import tf
 from math import *
-from geometry_msgs.msg import Twist, TransformStamped, Point32, PoseWithCovarianceStamped
 from sensor_msgs.msg import Range
-from nav_msgs.msg import Odometry
-from roboint.msg import Motor
 from roboint.msg import Inputs
 
 
@@ -14,124 +10,21 @@ class RoboExplorer:
        def __init__(self):
                rospy.init_node('robo_explorer')
 
-               self.x = 0
-               self.y = 0
-               self.alpha = 0
-               self.last_in = None
-               self.tf_broadcaster = tf.broadcaster.TransformBroadcaster()
                self.last_time = rospy.Time.now()
-               self.x_last = 0
-               self.y_last = 0
-               self.alpha_last = 0
-
-               # Distance between both wheels in meter (18.55cm)
-               self.wheel_dist = float(rospy.get_param('~wheel_dist', "0.1855"))
-               # Size of wheel Diameter in meter (5.15cm) * gear ratio (0.5) = 2.575cm 
-               self.wheel_size = float(rospy.get_param('~wheel_size', "0.02575"))
-               # Speed to PWM equation gradiant (The m in pwm = speed*m+b)
-               self.speed_gradiant = float(rospy.get_param('~speed_gradiant', "64.3"))
-               # Speed to PWM equation constant (The b in pwm = speed*m+b)
-               self.speed_constant = float(rospy.get_param('~speed_constant', "-1.7"))
-
-               self.pub_motor = rospy.Publisher("ft/set_motor", Motor, queue_size=16)
                self.pub_sonar = rospy.Publisher("sonar", Range, queue_size=16)
-               self.pub_odom = rospy.Publisher("odom", Odometry, queue_size=16)
-               
-               rospy.Subscriber("cmd_vel", Twist, self.cmdVelReceived)
                rospy.Subscriber("ft/get_inputs", Inputs, self.inputsReceived)
-               rospy.Subscriber("initialpose", PoseWithCovarianceStamped, self.posReceived)
 
                rospy.spin()
        
-       def posReceived(self, msg):
-               self.x = msg.pose.pose.position.x
-               self.y = msg.pose.pose.position.y
-               orientation = msg.pose.pose.orientation
-               angles = tf.transformations.euler_from_quaternion([orientation.x, orientation.y, orientation.z, orientation.w])
-               self.alpha = angles[2]
-
        def inputsReceived(self, msg):
                current_time = rospy.Time.now()
 
-               self.update_odometry(msg, current_time)
+               #self.update_odometry(msg, current_time)
                if (current_time - self.last_time).to_nsec() > 100e6: # send every 100ms
-                       self.send_odometry(msg, current_time)
+                       #self.send_odometry(msg, current_time)
                        self.send_range(msg, current_time)
                        self.last_time = current_time
 
-       def update_odometry(self, msg, current_time):
-               in_now = msg.input[:2]
-               if self.last_in is not None:
-                       in_diff = [abs(a - b) for a, b in zip(in_now, self.last_in)] # get changed inputs
-                       # fix in_diff from actual motor direction
-                       if msg.output[1] > 0: # left reverse
-                               in_diff[0] = -in_diff[0]
-                       elif msg.output[0] == 0 and msg.output[1] == 0: # left stop
-                               in_diff[0] = 0
-                       if msg.output[3] > 0: # right reverse
-                               in_diff[1] = -in_diff[1]
-                       elif msg.output[2] == 0 and msg.output[3] == 0: # right stop
-                               in_diff[1] = 0
-
-                       dist_dir = (in_diff[1] - in_diff[0]) * self.wheel_size*pi/8 # steps_changed in different direction => m
-                       delta_alpha = dist_dir/self.wheel_dist
-
-                       dist = (in_diff[0] + in_diff[1])/2.0 * self.wheel_size*pi/8 # steps_changed same direction => m
-
-                       delta_x = cos(self.alpha + delta_alpha/2)*dist
-                       delta_y = sin(self.alpha + delta_alpha/2)*dist
-
-                       self.alpha += delta_alpha
-                       if self.alpha > 2*pi:
-                               self.alpha -= 2*pi
-                       elif self.alpha < -2*pi:
-                               self.alpha += 2*pi
-                       self.x += delta_x
-                       self.y += delta_y
-
-               self.last_in = in_now
-
-       def send_odometry(self, msg, current_time):
-               # speeds
-               dt = (current_time - self.last_time).to_sec()
-               vx = sqrt((self.x - self.x_last)**2 + (self.y - self.y_last)**2) / dt
-               if (msg.output[0]-msg.output[1] + msg.output[2]-msg.output[3]) < 0:
-                       # moving backward
-                       vx*=-1
-               valpha = (self.alpha - self.alpha_last) / dt
-               self.x_last = self.x
-               self.y_last = self.y
-               self.alpha_last = self.alpha
-
-               # since all odometry is 6DOF we'll need a quaternion created from yaw
-               odom_quat = tf.transformations.quaternion_from_euler(0, 0, self.alpha)
-
-               # first, we'll publish the transform over tf
-               self.tf_broadcaster.sendTransform((self.x, self.y, 0.0), odom_quat, current_time, "base_link", "odom")
-
-               # next, we'll publish the odometry message over ROS
-               odom = Odometry()
-               odom.header.stamp = current_time
-               odom.header.frame_id = "/odom"
-
-               # set the position
-               odom.pose.pose.position.x = self.x
-               odom.pose.pose.position.y = self.y
-               odom.pose.pose.position.z = 0.0
-               odom.pose.pose.orientation.x = odom_quat[0]
-               odom.pose.pose.orientation.y = odom_quat[1]
-               odom.pose.pose.orientation.z = odom_quat[2]
-               odom.pose.pose.orientation.w = odom_quat[3]
-
-               # set the velocity
-               odom.child_frame_id = "base_link"
-               odom.twist.twist.linear.x = vx
-               odom.twist.twist.linear.y = 0.0
-               odom.twist.twist.angular.z = valpha
-
-               # publish the message
-               self.pub_odom.publish(odom)
-               
        def send_range(self, msg, current_time):
                # ultra sonic range finder
                scan = Range()
@@ -144,45 +37,5 @@ class RoboExplorer:
                scan.range = msg.d1/100.0
                self.pub_sonar.publish(scan)
 
-       # test with rostopic pub -1 cmd_vel geometry_msgs/Twist '[0, 0, 0]' '[0, 0, 0]'
-       def cmdVelReceived(self, msg):
-               trans = msg.linear.x
-               rot = msg.angular.z # rad/s
-
-               # handle rotation as offset to speeds
-               speed_offset = (rot * self.wheel_dist)/2.0 # m/s
-
-               # handle translation
-               speed_l = 0
-               wish_speed_left = trans - speed_offset
-               if abs(wish_speed_left) > 0:
-                       speed_l = self.speed_gradiant*abs(wish_speed_left) + self.speed_constant
-                       if wish_speed_left < 0:
-                               speed_l*=-1
-               speed_r = 0
-               wish_speed_right = trans + speed_offset
-               if abs(wish_speed_right) > 0:
-                       speed_r = self.speed_gradiant*abs(wish_speed_right) + self.speed_constant
-                       if wish_speed_right < 0:
-                               speed_r*=-1
-
-               # check limits
-               if speed_l < -7: speed_l = -7
-               elif speed_l > 7: speed_l = 7
-               if speed_r < -7: speed_r = -7
-               elif speed_r > 7: speed_r = 7
-
-               #print "Speed wanted: %.2f m/s %.2f rad/s, set: %d %d" % (trans, rot, round(speed_l), round(speed_r))
-
-               outmsg = Motor()
-               outmsg.num = 0
-               outmsg.speed = round(speed_l)
-               self.pub_motor.publish(outmsg)
-               
-               outmsg = Motor()
-               outmsg.num = 1
-               outmsg.speed = round(speed_r)
-               self.pub_motor.publish(outmsg)
-
 if __name__ == '__main__':
        RoboExplorer()
index 925dfd54ea37dd444717e126563e283ac6420850..63d710dcd063a1bd29d89d88d91a8cdb5aa99e15 100644 (file)
@@ -8,8 +8,8 @@
 
 
 static FT_TRANSFER_AREA *transfer_area = NULL;
-static char pwm[8] = {0};
-static char pwm_next[8] = {0};
+static int8_t pwm[8] = {0};
+static int8_t pwm_next[8] = {0};
 static pthread_mutex_t pwm_mutex = PTHREAD_MUTEX_INITIALIZER;
 
 void cb_set_output(const ::roboint::OutputConstPtr& msg) {
diff --git a/src/robo_explorer_hardware.cpp b/src/robo_explorer_hardware.cpp
new file mode 100644 (file)
index 0000000..457cdca
--- /dev/null
@@ -0,0 +1,31 @@
+#include "ros/ros.h"
+#include "robo_explorer_hardware.h"
+#include "controller_manager/controller_manager.h"
+
+int main(int argc, char **argv) {
+       ros::init(argc, argv, "robo_explorer_hardware");
+
+       ros::NodeHandle n;
+
+       RoboExplorer robot(n);
+       controller_manager::ControllerManager cm(&robot);
+
+       ros::AsyncSpinner spinner(1);
+       spinner.start();
+
+       ros::Time prev_time = ros::Time::now();
+       ros::Rate loop_rate(10);
+       while(ros::ok()) {
+               const ros::Time time = ros::Time::now();
+               const ros::Duration period = time - prev_time;
+
+               robot.read(period);
+               cm.update(time, period);
+               robot.write();
+
+               prev_time = time;
+               loop_rate.sleep();
+       }
+
+       return 0;
+}
index a32a1afaf50f840506c4e0c2f88182c3e67348b9..8f44ce2927fc3397b5d818b83261ec529b129600 100644 (file)
                                <color rgba="0 0 0 1"/>
                        </material>
                </visual>
+               <collision>
+                       <geometry>
+                               <cylinder radius="0.026" length="0.02"/>
+                       </geometry>
+               </collision>
        </link>
 
        <link name="right_wheel">
                                <color rgba="0 0 0 1"/>
                        </material>
                </visual>
+               <collision>
+                       <geometry>
+                               <cylinder radius="0.026" length="0.02"/>
+                       </geometry>
+               </collision>
        </link>
 
        <link name="aft_wheel">
                <child link="forward_sensor"/>
                <origin xyz="0.07 0 0.06" rpy="0 0 0"/>
        </joint>
+
+       <transmission name="left_wheel_trans" type="SimpleTransmission">
+               <type>transmission_interface/SimpleTransmission</type>
+               <joint name="left_wheel_joint">
+                       <hardwareInterface>VelocityJointInterface</hardwareInterface>
+               </joint>
+               <actuator name="left_wheel_motor">
+                       <mechanicalReduction>1</mechanicalReduction>
+               </actuator>
+       </transmission>
+
+       <transmission name="right_wheel_trans" type="SimpleTransmission">
+               <type>transmission_interface/SimpleTransmission</type>
+               <joint name="right_wheel_joint">
+                       <hardwareInterface>VelocityJointInterface</hardwareInterface>
+               </joint>
+               <actuator name="right_wheel_motor">
+                       <mechanicalReduction>1</mechanicalReduction>
+               </actuator>
+       </transmission>
 </robot>