Skip to content

Instantly share code, notes, and snippets.

@mikehamer
Created January 17, 2017 16:42
Show Gist options
  • Star 0 You must be signed in to star a gist
  • Fork 2 You must be signed in to fork a gist
  • Save mikehamer/1d3e7c3f03dfdbc3a5fc302804dcdba5 to your computer and use it in GitHub Desktop.
Save mikehamer/1d3e7c3f03dfdbc3a5fc302804dcdba5 to your computer and use it in GitHub Desktop.
#!/usr/local/bin/python
import rospy
import tf
from sensor_msgs.msg import Joy
from geometry_msgs.msg import Twist
from crazyflie_driver.srv import UpdateParams
from crazyflie_driver.msg import GenericLogData
from crazyflie_driver.msg import FullControl
from std_srvs.srv import Empty
from geometry_msgs.msg import PoseStamped
from numpy import *
from math import radians
LOOP_RATE = 30 # Hz
# command pos: 0b111
# command vel: 0b011
# command acc: 0b001
XMODE = 0b111
YMODE = 0b111
ZMODE = 0b111
# I suggest starting by commanding the accelerations on all axes (0b001, 0b001, 0b001)
# Then command x and y velocity, and z position so it holds the height (0b011, 0b011, 0b111)
# Then command all positions (0b111, 0b111, 0b111)
class Controller():
def __init__(self, name, joy_topic, frame, worldFrame):
self._name = name
self._frame = frame
self._worldFrame = worldFrame
self._state = [0,0,0,0,0,0]
self._sensor = [0]
self._home = [0,0,0]
self._buttons = None
self._cmd = FullControl()
self._cmd.enable = False
self._cmd.xmode = XMODE
self._cmd.ymode = YMODE
self._cmd.zmode = ZMODE
self._cmd.x = [0,0,0]
self._cmd.y = [0,0,0]
self._cmd.z = [0,0,0]
self._cmd.yaw = [0,0]
rospy.wait_for_service('update_params')
self._update_params = rospy.ServiceProxy('update_params', UpdateParams)
rospy.set_param("ctrlr/coll_fairness", 0)
rospy.set_param("ctrlr/mixing_factor", 1.0)
rospy.set_param("ctrlr/tau_xy", 0.3)
rospy.set_param("ctrlr/zeta_xy", 0.85)
rospy.set_param("ctrlr/tau_z", 0.3)
rospy.set_param("ctrlr/zeta_z", 0.85)
rospy.set_param("ctrlr/tau_rp", 0.25)
rospy.set_param("ctrlr/tau_rp_rate", 0.015)
rospy.set_param("ctrlr/tau_yaw_rate", 0.0075)
rospy.set_param("ctrlr/coll_min", 5)
rospy.set_param("ctrlr/coll_max", 15)
rospy.set_param("ctrlr/omega_rp_max", 30)
rospy.set_param("ctrlr/omega_yaw_max", 10)
rospy.set_param("ctrlr/igain_yaw", 0.01)
rospy.set_param("ctrlr/imax_yaw", 3.14)
rospy.set_param("ctrlr/igain_rate", 0)
self._update_params(["ctrlr/coll_fairness",
"ctrlr/tau_xy",
"ctrlr/zeta_xy",
"ctrlr/tau_z",
"ctrlr/zeta_z",
"ctrlr/tau_rp",
"ctrlr/mixing_factor",
"ctrlr/tau_rp_rate",
"ctrlr/tau_yaw_rate",
"ctrlr/coll_min",
"ctrlr/coll_max",
"ctrlr/omega_rp_max",
"ctrlr/omega_yaw_max",
"ctrlr/igain_yaw",
"ctrlr/imax_yaw",
"ctrlr/igain_rate"])
self._control_pub = rospy.Publisher("full_control", FullControl, queue_size=1, latch=True)
rospy.Subscriber(joy_topic, Joy, self._joyChanged)
rospy.Subscriber('/{}/measured'.format(name), GenericLogData, self._stateChanged)
rospy.loginfo("Controller initialized for {}".format(name))
def run(self):
rate = rospy.Rate(LOOP_RATE)
while not rospy.is_shutdown():
rate.sleep()
self._control_pub.publish(self._cmd)
def _joyChanged(self, data):
for i in range(0, len(data.buttons)):
if self._buttons == None or data.buttons[i] != self._buttons[i]:
if i==0 and data.buttons[i] == 1:
self._cmd.enable = False
rospy.loginfo("Disabled!")
if i==2 and data.buttons[i] == 1:
self._cmd.enable = True
self._home = [self._state[0], self._state[1], self._state[2]]
rospy.loginfo("Enabled!")
if i==8 and data.buttons[i] == 1:
self._cmd.yaw = [self._cmd.yaw[0]-pi/4, 0]
rospy.loginfo("Yaw={}".format(int(self._cmd.yaw[0]*180/pi)))
if i==9 and data.buttons[i] == 1:
self._cmd.yaw = [self._cmd.yaw[0]+pi/4, 0]
rospy.loginfo("Yaw={}".format(int(self._cmd.yaw[0]*180/pi)))
if i == 11 and data.buttons[i] == 1:
rospy.loginfo("resetEstimation = {}".format(data.buttons[i]))
rospy.set_param("kalman/resetEstimation", data.buttons[i])
self._update_params(["kalman/resetEstimation"])
self._buttons = data.buttons
# When commanding acceleration, joystick commands are converted to accelerations
# When commanding velocity, joystick commands are converted to velocities
# When commanding position, joystick commands are converted to a position on a square centered at the takeoff position, and with side length +/- 2 meters from the center.
if XMODE==0:
self._cmd.x = [0,0,0]
elif XMODE==0b001:
self._cmd.x = [0,0,5*data.axes[1]]
elif XMODE==0b010 or XMODE==0b011:
self._cmd.x = [0,3*data.axes[1],0]
else:
self._cmd.x = [self._home[0]+2*data.axes[1],0,0]
if YMODE==0:
self._cmd.y = [0,0,0]
elif YMODE==0b001:
self._cmd.y = [0,0,5*data.axes[0]]
elif YMODE==0b010 or YMODE==0b011:
self._cmd.y = [0,3*data.axes[0],0]
else:
self._cmd.y = [self._home[1]+2*data.axes[0],0,0]
if ZMODE==0:
self._cmd.z = [0,0,0]
elif ZMODE==0b001:
self._cmd.z = [0,0,5*data.axes[3]]
elif ZMODE==0b010 or ZMODE==0b011:
self._cmd.z = [0,3*data.axes[3],0]
else:
self._cmd.z = [data.axes[3]+1,0,0]
def _stateChanged(self, state):
self._state = list(state.values)
br = tf.TransformBroadcaster()
x, y, z, roll, pitch, yaw = self._state
br.sendTransform(
(x, y, z),
tf.transformations.quaternion_from_euler(radians(roll), -radians(pitch), radians(yaw)),
rospy.Time.now(),
'{}'.format(self._frame),
self._worldFrame)
if __name__ == '__main__':
rospy.init_node('crazyflie_controller', anonymous=True)
name = rospy.get_namespace().strip('/')
worldFrame = rospy.get_param("~worldFrame", "world")
frame = rospy.get_param("~frame")
joy_topic = rospy.get_param("~joy_topic", "joy")
controller = Controller(name, joy_topic, frame, worldFrame)
controller.run()
rospy.spin()
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment