import roslib; roslib.load_manifest('roboint')
import rospy
import tf
-from math import sin, cos, pi
-from geometry_msgs.msg import Twist, TransformStamped, Point32
-from sensor_msgs.msg import LaserScan
+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
def __init__(self):
rospy.init_node('robo_explorer')
- self.wheel_dist = 0.188 # 18.8cm
- self.wheel_size = 0.052*0.5 # 5.2cm; gear ration=0.5
- self.speed = (0, 0)
self.x = 0
self.y = 0
self.alpha = 0
self.last_in = None
- self.tf_broadcaster = tf.TransformBroadcaster()
+ self.tf_broadcaster = tf.broadcaster.TransformBroadcaster()
self.last_time = rospy.Time.now()
- self.input_count = 0
self.x_last = 0
self.y_last = 0
self.alpha_last = 0
- self.pub_motor = rospy.Publisher("ft/set_motor", Motor)
- self.pub_scan = rospy.Publisher("scan", LaserScan)
- self.pub_odom = rospy.Publisher("odom", Odometry)
+ # 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.input_count+=1
self.update_odometry(msg, current_time)
- if self.input_count >= 10:
- self.input_count = 0
- self.tf_broadcaster.sendTransform((0.0, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0), current_time, "odom", "map");
+ if (current_time - self.last_time).to_nsec() > 100e6: # send every 100ms
self.send_odometry(msg, current_time)
- self.send_laser_scan(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[1:3]
+ 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 self.speed[0] < 0:
+ if msg.output[1] > 0: # left reverse
in_diff[0] = -in_diff[0]
- elif self.speed[0] == 0:
+ elif msg.output[0] == 0 and msg.output[1] == 0: # left stop
in_diff[0] = 0
- if self.speed[1] < 0:
+ if msg.output[3] > 0: # right reverse
in_diff[1] = -in_diff[1]
- elif self.speed[1] == 0:
+ 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
+ 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
+ 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
def send_odometry(self, msg, current_time):
# speeds
dt = (current_time - self.last_time).to_sec()
- vx = (self.x - self.x_last) / dt
- vy = (self.y - self.y_last) / dt
+ 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.last_time = current_time
self.x_last = self.x
self.y_last = self.y
self.alpha_last = self.alpha
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");
+ 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.pose.pose.orientation.w = odom_quat[3]
# set the velocity
- odom.child_frame_id = "base_link";
+ odom.child_frame_id = "base_link"
odom.twist.twist.linear.x = vx
- odom.twist.twist.linear.y = vy
+ odom.twist.twist.linear.y = 0.0
odom.twist.twist.angular.z = valpha
# publish the message
self.pub_odom.publish(odom)
- def send_laser_scan(self, msg, current_time):
- # first, we'll publish the transform over tf
- self.tf_broadcaster.sendTransform((0.06, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0), current_time, "scan", "base_link");
-
- # actually ultra sonic range finder
- scan = LaserScan()
+ def send_range(self, msg, current_time):
+ # ultra sonic range finder
+ scan = Range()
scan.header.stamp = current_time
- scan.header.frame_id = "/scan"
- scan.angle_min = -pi/4;
- scan.angle_max = pi/4;
- scan.angle_increment = pi/4;
- scan.time_increment = 0.1;
- scan.range_min = 0.0;
- scan.range_max = 4.0;
- for i in range(3):
- scan.ranges.append(msg.d1/100.0)
- scan.intensities.append(0.5)
- scan.intensities.append(1.0)
- scan.intensities.append(0.5)
- self.pub_scan.publish(scan)
+ scan.header.frame_id = "forward_sensor"
+ scan.radiation_type = 0
+ scan.field_of_view = 60*pi/180
+ scan.min_range = 0.0
+ scan.max_range = 4.0
+ 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):
# handle translation
speed_l = 0
wish_speed_left = trans - speed_offset
- if abs(wish_speed_left) > 1.7/64.3:
- speed_l = 64.3*abs(wish_speed_left) - 1.7
+ 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) > 1.7/64.3:
- speed_r = 64.3*abs(wish_speed_right) - 1.7
+ 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
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 = 1
+ outmsg.num = 0
outmsg.speed = round(speed_l)
self.pub_motor.publish(outmsg)
outmsg = Motor()
- outmsg.num = 2
+ outmsg.num = 1
outmsg.speed = round(speed_r)
self.pub_motor.publish(outmsg)
- self.speed = (speed_l, speed_r)
-
if __name__ == '__main__':
RoboExplorer()