Commit 5c846cee authored by Mugisha David's avatar Mugisha David

upd

parents
cmake_minimum_required(VERSION 2.8.3)
project(rover_driver_base)
## 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
geometry_msgs
rospy
sensor_msgs
std_msgs
tf
)
## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)
## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
catkin_python_setup()
################################################
## Declare ROS messages, services and actions ##
################################################
## To declare and build messages, services or actions from within this
## package, follow these steps:
## * Let MSG_DEP_SET be the set of packages whose message types you use in
## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
## * In the file package.xml:
## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET
## * If MSG_DEP_SET isn't empty the following dependencies might have been
## pulled in transitively but can be declared for certainty nonetheless:
## * add a build_depend tag for "message_generation"
## * add a run_depend tag for "message_runtime"
## * In this file (CMakeLists.txt):
## * add "message_generation" and every package in MSG_DEP_SET to
## find_package(catkin REQUIRED COMPONENTS ...)
## * add "message_runtime" and every package in MSG_DEP_SET to
## catkin_package(CATKIN_DEPENDS ...)
## * uncomment the add_*_files sections below as needed
## and list every .msg/.srv/.action file to be processed
## * uncomment the generate_messages entry below
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
## Generate messages in the 'msg' folder
# add_message_files(
# FILES
# Message1.msg
# Message2.msg
# )
## Generate services in the 'srv' folder
# add_service_files(
# FILES
# Service1.srv
# Service2.srv
# )
## Generate actions in the 'action' folder
# add_action_files(
# FILES
# Action1.action
# Action2.action
# )
## Generate added messages and services with any dependencies listed here
# generate_messages(
# DEPENDENCIES
# geometry_msgs# sensor_msgs# std_msgs
# )
###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if you package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
# INCLUDE_DIRS include
# LIBRARIES rover_driver_base
# CATKIN_DEPENDS geometry_msgs rospy sensor_msgs std_msgs tf
# DEPENDS system_lib
)
###########
## Build ##
###########
## Specify additional locations of header files
## Your package locations should be listed before other locations
# include_directories(include)
include_directories(
${catkin_INCLUDE_DIRS}
)
## Declare a cpp library
# add_library(rover_driver_base
# src/${PROJECT_NAME}/rover_driver_base.cpp
# )
## Declare a cpp executable
# add_executable(rover_driver_base_node src/rover_driver_base_node.cpp)
## Add cmake target dependencies of the executable/library
## as an example, message headers may need to be generated before nodes
# add_dependencies(rover_driver_base_node rover_driver_base_generate_messages_cpp)
## Specify libraries to link a library or executable target against
# target_link_libraries(rover_driver_base_node
# ${catkin_LIBRARIES}
# )
#############
## Install ##
#############
install(PROGRAMS
nodes/rover_command.py
nodes/rover_odom.py
nodes/rover_teleop.py
nodes/rover_keyboard.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
install(DIRECTORY src/rover_driver/
DESTINATION ${CATKIN_PACKAGE_PYTHON_DESTINATION}
USE_SOURCE_PERMISSIONS
PATTERN ".svn" EXCLUDE
)
# all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
# install(PROGRAMS
# scripts/my_python_script
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark executables and/or libraries for installation
# install(TARGETS rover_driver_base rover_driver_base_node
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark cpp header files for installation
# install(DIRECTORY include/${PROJECT_NAME}/
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
# FILES_MATCHING PATTERN "*.h"
# PATTERN ".svn" EXCLUDE
# )
## Mark other files for installation (e.g. launch and bag files, etc.)
# install(FILES
# # myfile1
# # myfile2
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
# )
#############
## Testing ##
#############
## Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_rover_driver_base.cpp)
# if(TARGET ${PROJECT_NAME}-test)
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
# endif()
## Add folders to be run by python nosetests
# catkin_add_nosetests(test)
<launch>
<!-- joy node -->
<node respawn="true" pkg="joy" type="joy_node" name="joy" >
<!-- <param name="dev" type="string" value="/dev/input/js0" /> -->
<!-- <param name="deadzone" value="0.12" /> -->
<param name="autorepeat_rate" value="10.0" />
</node>
<!-- Axes -->
<node pkg="rover_driver_base" type="rover_teleop.py" name="teleop">
<param name="axis_linear_x" value="1" type="int"/>
<param name="axis_linear_y" value="0" type="int"/>
<param name="axis_angular" value="3" type="int"/>
<param name="scale_linear" value="1.0" type="double"/>
<param name="scale_angular" value="0.7" type="double"/>
<remap from="/teleop/joy" to="/joy"/>
<remap from="/teleop/twistCommand" to="/rover/twistCommand"/>
</node>
<node pkg="rover_driver_base" type="rover_command.py" name="rover" output="screen">
<param name="rover_name" value="rover"/>
<param name="skidsteer" value="false"/>
</node>
</launch>
<launch>
<!-- joy node -->
<node respawn="true" pkg="joy" type="joy_node" name="joy" >
<!-- <param name="dev" type="string" value="/dev/input/js0" /> -->
<!-- <param name="deadzone" value="0.12" /> -->
<param name="autorepeat_rate" value="10.0" />
</node>
<!-- Axes -->
<node pkg="rover_driver_base" type="rover_teleop.py" name="teleop">
<param name="axis_linear_x" value="1" type="int"/>
<param name="axis_linear_y" value="0" type="int"/>
<param name="axis_angular" value="3" type="int"/>
<param name="scale_linear" value="1.0" type="double"/>
<param name="scale_angular" value="0.7" type="double"/>
<remap from="/teleop/joy" to="/joy"/>
<remap from="/teleop/twistCommand" to="/rover/twistCommand"/>
</node>
<node pkg="rover_driver_base" type="rover_command.py" name="rover" output="screen">
<param name="rover_name" value="rover"/>
<param name="skidsteer" value="false"/>
</node>
<node pkg="rover_driver_base" type="rover_odom.py" name="odom" output="screen">
<param name="rover_name" value="rover"/>
</node>
</launch>
#!/usr/bin/env python
import roslib; roslib.load_manifest('rover_driver_base')
import rospy
from std_msgs.msg import Float64
from sensor_msgs.msg import JointState
from geometry_msgs.msg import Twist,Pose
from math import atan2, hypot, pi, cos, sin
import tf
import message_filters
import numpy
from numpy.linalg import pinv
from rover_driver_base.rover_kinematics import *
class RoverDriver:
def __init__(self,name):
self.name = name
rospy.init_node('rover_driver')
self.name = rospy.get_param("~rover_name",self.name)
self.skidsteer = rospy.get_param("~skidsteer",False)
self.check_timeout = rospy.get_param("~check_timeout",True)
rospy.loginfo("Starting rover driver for rover '%s'" % self.name)
self.last_cmd = rospy.Time.now()
self.listener = tf.TransformListener()
self.steering_pub={}
self.drive_pub={}
self.ready = False
self.kinematics = RoverKinematics()
self.twist_sub = rospy.Subscriber('~twistCommand', Twist, self.twist_cb)
# print "Initialising wheel data structure"
for k in prefix:
self.steering_pub[k] = rospy.Publisher("/vrep/%s/%sSteerCommand" % (self.name,k), Float64, queue_size=1)
self.drive_pub[k] = rospy.Publisher("/vrep/%s/%sDriveCommand" % (self.name,k), Float64, queue_size=1)
def twist_cb(self,twist):
if not self.ready:
return
# print "Got twist: " + str(twist)
self.last_cmd = rospy.Time.now()
# Get the pose of all drives
drive_cfg={}
for k in prefix:
# try:
# self.listener.waitForTransform('/%s/ground'%(self.name),
# '/%s/%sDrive'%(self.name,k), self.last_cmd, rospy.Duration(1.0))
((x,y,z),rot) = self.listener.lookupTransform('/%s/ground'%(self.name),
'/%s/%sDrive'%(self.name,k), rospy.Time(0))
drive_cfg[k] = DriveConfiguration(self.radius[k],x,y,z)
# except (tf.LookupException, tf.ConnectivityException, tf.ExtrapolationException):
# return
# Now compute for each drive, its rotation speed and steering angle
motors = self.kinematics.twist_to_motors(twist,drive_cfg,self.skidsteer)
self.publish(motors)
def publish(self, motor):
for k in prefix:
self.drive_pub[k].publish(Float64(motor.drive[k]))
self.steering_pub[k].publish(Float64(motor.steering[k]))
def run(self):
timeout = True
rate = rospy.Rate(10)
rospy.loginfo("Waiting for initial transforms")
rospy.sleep(1.0)
self.radius={}
for k in prefix:
try:
self.listener.waitForTransform('/%s/ground'%(self.name),
'/%s/%sDrive'%(self.name,k), rospy.Time(0), rospy.Duration(5.0))
((x,y,z),rot) = self.listener.lookupTransform('/%s/ground'%(self.name),
'/%s/%sDrive'%(self.name,k), rospy.Time(0))
self.radius[k] = z
rospy.loginfo("Got transform for " + k)
except tf.Exception,e:
rospy.logerr("TF exception: " + repr(e))
self.ready = True
while not rospy.is_shutdown():
if self.check_timeout:
if (rospy.rostime.get_time() - self.last_cmd.to_sec()) < 0.5:
if timeout:
timeout = False
rospy.loginfo("Accepting joystick commands")
else:
if not timeout:
timeout = True
rospy.loginfo("Timeout: ignoring joystick commands")
motors = RoverMotors()
self.publish(motors)
rate.sleep()
if __name__ == '__main__':
try:
rd = RoverDriver("rover")
rd.run()
except rospy.ROSInterruptException:
pass
#!/usr/bin/env python
# source for this file:
# http://ftp.isr.ist.utl.pt/pub/roswiki/stage%282f%29Tutorials%282f%29SimulatingOneRobot.html
import roslib; roslib.load_manifest('rover_driver_base')
import rospy
from geometry_msgs.msg import Twist
import sys, select, termios, tty
msg = """
Reading from the keyboard and Publishing to Twist!
---------------------------
Moving around:
u i o
j k l
m , .
q/z : increase/decrease max speeds by 10%
w/x : increase/decrease only linear speed by 10%
e/c : increase/decrease only angular speed by 10%
anything else : stop
CTRL-C to quit
"""
moveBindings = {
'i':(1,0),
'o':(1,-1),
'j':(0,1),
'l':(0,-1),
'k':(0,0),
'u':(1,1),
',':(-1,0),
'.':(-1,1),
'm':(-1,-1),
}
angularBindings = {
'a':+1,
's':0,
'd':-1,
}
speedBindings={
'q':(1.1,1.1),
'z':(.9,.9),
'w':(1.1,1),
'x':(.9,1),
'e':(1,1.1),
'c':(1,.9),
}
def getKey():
tty.setraw(sys.stdin.fileno())
select.select([sys.stdin], [], [], 0)
key = sys.stdin.read(1)
termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)
return key
speed = .5
turn = 1
def vels(speed,turn):
return "currently:\tspeed %s\tturn %s " % (speed,turn)
if __name__=="__main__":
settings = termios.tcgetattr(sys.stdin)
rospy.init_node('teleop_twist_keyboard')
twist_topic = rospy.resolve_name("output")
pub = rospy.Publisher(twist_topic, Twist)
x = 0
y = 0
th = 0
status = 0
try:
print msg
print vels(speed,turn)
while(1):
key = getKey()
if key in moveBindings.keys():
x,y = moveBindings[key]
print "Direction: %.1f %.1f" % (x*speed,y*speed)
elif key in angularBindings.keys():
th = angularBindings[key]
print "Angular: %.1f " % th
elif key in speedBindings.keys():
speed = speed * speedBindings[key][0]
turn = turn * speedBindings[key][1]
print vels(speed,turn)
if (status == 14):
print msg
status = (status + 1) % 15
else:
x = 0
th = 0
if (key == '\x03'):
break
twist = Twist()
twist.linear.x = x*speed;
twist.linear.y = y*speed;
twist.linear.z = 0
twist.angular.x = 0;
twist.angular.y = 0;
twist.angular.z = th*turn
pub.publish(twist)
except e:
print e
finally:
twist = Twist()
twist.linear.x = 0; twist.linear.y = 0; twist.linear.z = 0
twist.angular.x = 0; twist.angular.y = 0; twist.angular.z = 0
pub.publish(twist)
termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)
#!/usr/bin/env python
import roslib; roslib.load_manifest('rover_driver_base')
import rospy
from std_msgs.msg import Float64
from sensor_msgs.msg import JointState
from geometry_msgs.msg import Twist,Pose
from math import atan2, hypot, pi, cos, sin
import tf
import message_filters
import numpy
from numpy.linalg import pinv
from rover_driver_base.rover_kinematics import *
class RoverDriver:
def __init__(self,name):
self.name = name
rospy.init_node('rover_odom')
self.name = rospy.get_param("~rover_name",self.name)
rospy.loginfo("Starting rover odometry for rover '%s'" % self.name)
self.last_cmd = rospy.Time.now()
self.listener = tf.TransformListener()
self.broadcaster = tf.TransformBroadcaster()
self.steering_sub={}
self.drive_sub={}
self.ready = False
self.connected = False
self.kinematics = RoverKinematics()
# print "Initialising wheel data structure"
for k in prefix:
self.steering_sub[k] = message_filters.Subscriber("/vrep/%s/%sSteerEncoder" % (self.name,k), JointState)
self.drive_sub[k] = message_filters.Subscriber("/vrep/%s/%sDriveEncoder" % (self.name,k), JointState)
# print "Initialised wheel " + k
self.ts = message_filters.TimeSynchronizer(self.steering_sub.values()+self.drive_sub.values(), 10)
self.ts.registerCallback(self.sync_odo_cb)
def sync_odo_cb(self,*args):
self.connected = True
if not self.ready:
return
if len(args)!=12:
rospy.logerr("Invalid number of argument in OdoCallback")
return
steering_val = [s.position[0] for s in args[0:6]]
drive_val = [s.position[0] for s in args[6:12]]
motors = RoverMotors()
motors.steering = dict(zip(self.steering_sub.keys(),steering_val))
motors.drive = dict(zip(self.drive_sub.keys(),drive_val))
self.odo_cb(args[0].header.stamp,motors)
def odo_cb(self,timestamp,motors):
# Get the pose of all drives
drive_cfg={}
for k in prefix:
# try:
# self.listener.waitForTransform('/%s/ground'%(self.name),
# '/%s/%sDrive'%(self.name,k), self.last_cmd, rospy.Duration(1.0))
((x,y,z),rot) = self.listener.lookupTransform('/%s/ground'%(self.name),
'/%s/%sDrive'%(self.name,k), rospy.Time(0))
drive_cfg[k] = DriveConfiguration(self.radius[k],x,y,z)
# except (tf.LookupException, tf.ConnectivityException, tf.ExtrapolationException):
# return
X = self.kinematics.integrate_odometry(motors, drive_cfg)
self.broadcaster.sendTransform((X[0,0], X[1,0], 0),
tf.transformations.quaternion_from_euler(0, 0, X[2,0]),
timestamp, "/%s/ground"%self.name, "/odom")
# finally store the value of the motor state
def run(self):
timeout = True
rate = rospy.Rate(2)
rospy.loginfo("Waiting for VREP")
while (not rospy.is_shutdown()) and (not self.connected):
rate.sleep()
if rospy.is_shutdown():
return
rospy.loginfo("Waiting for initial transforms")
rospy.sleep(1.0)
self.radius={}
for k in prefix:
try:
self.listener.waitForTransform('/%s/ground'%(self.name),
'/%s/%sDrive'%(self.name,k), rospy.Time(0), rospy.Duration(5.0))
((x,y,z),rot) = self.listener.lookupTransform('/%s/ground'%(self.name),
'/%s/%sDrive'%(self.name,k), rospy.Time(0))
self.radius[k] = z
rospy.loginfo("Got transform for " + k)
except tf.Exception,e:
rospy.logerr("TF exception: " + repr(e))
self.ready = True
while not rospy.is_shutdown():
rate.sleep()
if __name__ == '__main__':
try:
rd = RoverDriver("rover")
rd.run()
except rospy.ROSInterruptException:
pass
#!/usr/bin/env python
import roslib; roslib.load_manifest('rover_driver_base')
import rospy
from sensor_msgs.msg import Joy
from geometry_msgs.msg import Twist
last_joy = -1e10
joy_value = None
def joy_cb(value):
global joy_value
global last_joy
last_joy = rospy.rostime.get_time()
joy_value = value
def talker():
global joy_value
global last_joy
rospy.init_node('vrep_ros_teleop')
sub = rospy.Subscriber('~joy', Joy, joy_cb)
pub = rospy.Publisher('~twistCommand', Twist, queue_size=1)
axis_linear_x = rospy.get_param("~axis_linear_x",1)
axis_linear_y = rospy.get_param("~axis_linear_y",0)
axis_angular = rospy.get_param("~axis_angular",3)
scale_linear = rospy.get_param("~scale_linear",5.)
scale_angular = rospy.get_param("~scale_angular",10.)
timeout = True
while not rospy.is_shutdown():
twist = Twist()
if (rospy.rostime.get_time() - last_joy) < 0.5:
if timeout:
timeout = False
rospy.loginfo("Accepting joystick commands")
twist.linear.x = joy_value.axes[axis_linear_x] * scale_linear
twist.linear.y = joy_value.axes[axis_linear_y] * scale_linear
twist.angular.z = joy_value.axes[axis_angular] * scale_angular
# if twist.linear.x < 0:
# twist.angular.z = - twist.angular.z
else:
if not timeout:
timeout = True
rospy.loginfo("Timeout: ignoring joystick commands")
pub.publish(twist)
rospy.sleep(0.1)
if __name__ == '__main__':
try:
talker()
except rospy.ROSInterruptException:
pass
<?xml version="1.0"?>
<package>
<name>rover_driver_base</name>
<version>0.0.0</version>
<description>The rover_driver_base package</description>
<!-- One maintainer tag required, multiple allowed, one person per tag -->
<!-- Example: -->
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
<maintainer email="cedricp@todo.todo">cedricp</maintainer>
<!-- One license tag required, multiple allowed, one license per tag -->
<!-- Commonly used license strings: -->
<!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
<license>TODO</license>
<!-- Url tags are optional, but mutiple are allowed, one per tag -->
<!-- Optional attribute type can be: website, bugtracker, or repository -->
<!-- Example: -->
<!-- <url type="website">http://wiki.ros.org/rover_driver_base</url> -->
<!-- Author tags are optional, mutiple are allowed, one per tag -->
<!-- Authors do not have to be maintianers, but could be -->
<!-- Example: -->
<!-- <author email="jane.doe@example.com">Jane Doe</author> -->
<!-- The *_depend tags are used to specify dependencies -->
<!-- Dependencies can be catkin packages or system dependencies -->
<!-- Examples: -->
<!-- Use build_depend for packages you need at compile time: -->
<!-- <build_depend>message_generation</build_depend> -->
<!-- Use buildtool_depend for build tool packages: -->
<!-- <buildtool_depend>catkin</buildtool_depend> -->
<!-- Use run_depend for packages you need at runtime: -->
<!-- <run_depend>message_runtime</run_depend> -->
<!-- Use test_depend for packages you need only for testing: -->
<!-- <test_depend>gtest</test_depend> -->
<buildtool_depend>catkin</buildtool_depend>
<build_depend>geometry_msgs</build_depend>
<build_depend>rospy</build_depend>
<build_depend>sensor_msgs</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>tf</build_depend>
<run_depend>geometry_msgs</run_depend>
<run_depend>rospy</run_depend>
<run_depend>sensor_msgs</run_depend>
<run_depend>std_msgs</run_depend>
<run_depend>tf</run_depend>
<!-- The export tag contains other, unspecified, tags -->
<export>
<!-- You can specify that this package is a metapackage here: -->
<!-- <metapackage/> -->
<!-- Other tools can request additional information be placed here -->
</export>
</package>
\ No newline at end of file
#!/usr/bin/env python
from distutils.core import setup
from catkin_pkg.python_setup import generate_distutils_setup
d = generate_distutils_setup(
install_requires=['rospy'],
packages=['rover_driver_base'],
package_dir={'': 'src'}
)
setup(**d)
#!/usr/bin/env python
import roslib; roslib.load_manifest('rover_driver_base')
import rospy
from geometry_msgs.msg import Twist
import numpy
from numpy.linalg import pinv
from math import atan2, hypot, pi, cos, sin
prefix=["FL","FR","CL","CR","RL","RR"]
class RoverMotors:
def __init__(self):
self.steering={}
self.drive={}
for k in prefix:
self.steering[k]=0.0
self.drive[k]=0.0
def copy(self,value):
for k in prefix:
self.steering[k]=value.steering[k]
self.drive[k]=value.drive[k]
class DriveConfiguration:
def __init__(self,radius,x,y,z):
self.x = x
self.y = y
self.z = z
self.radius = radius
class RoverKinematics:
def __init__(self):
self.X = numpy.asmatrix(numpy.zeros((3,1)))
self.motor_state = RoverMotors()
self.first_run = True
def twist_to_motors(self, twist, drive_cfg, skidsteer=False):
motors = RoverMotors()
if skidsteer:
for k in drive_cfg.keys():