diff --git a/pps_ws/src/d_fall_pps/CMakeLists.txt b/pps_ws/src/d_fall_pps/CMakeLists.txt index 8c96bd4fec9b5840965a5f99ac91b9bde21b5f12..0550d2dc9c9f84ecbb5e9aa9cfdb3529cb542dde 100644 --- a/pps_ws/src/d_fall_pps/CMakeLists.txt +++ b/pps_ws/src/d_fall_pps/CMakeLists.txt @@ -58,9 +58,9 @@ find_package(catkin REQUIRED COMPONENTS add_message_files( FILES ViconData.msg - MotorControl.msg - AngleControl.msg - RateControl.msg + MotorCommand.msg + AngleCommand.msg + RateCommand.msg Setpoint.msg ) diff --git a/pps_ws/src/d_fall_pps/crazyradio/CrazyRadio.py b/pps_ws/src/d_fall_pps/crazyradio/CrazyRadio.py index ad4ad27a273c5dd12895bc54e47cbcdc354102a2..f05cac2ba464c80f14bbf41344297d1e764130ac 100755 --- a/pps_ws/src/d_fall_pps/crazyradio/CrazyRadio.py +++ b/pps_ws/src/d_fall_pps/crazyradio/CrazyRadio.py @@ -64,24 +64,20 @@ class PPSRadioClient: This callback is executed as soon as the connection to the quadrotor is established. """ - #print "Connection to %s successful: " % link_uri rospy.loginfo("Connection to %s successful: " % link_uri) def _connection_failed(self, link_uri, msg): """Callback when connection initial connection fails (i.e no Crazyflie at the specified address)""" - #print "Connection to %s failed: %s" % (link_uri, msg) rospy.logerr("Connection to %s failed: %s" % (link_uri, msg)) def _connection_lost(self, link_uri, msg): """Callback when disconnected after a connection has been made (i.e Crazyflie moves out of range)""" - #print "Connection to %s lost: %s" % (link_uri, msg) rospy.logerr("Connection to %s lost: %s" % (link_uri, msg)) def _disconnected(self, link_uri): """Callback when the Crazyflie is disconnected (called in all cases)""" - #print "Disconnected from %s" % link_uri rospy.logwarn("Disconnected from %s" % link_uri) def _send_to_commander(self,roll, pitch, yaw, thrust,cmd1,cmd2,cmd3,cmd4,mode): @@ -108,12 +104,11 @@ def rateControlCallback(data): if __name__ == '__main__': rospy.init_node('CrazyRadio', anonymous=True) + # Initialize the low-level drivers (don't list the debug drivers) cflib.crtp.init_drivers(enable_debug_driver=False) while not rospy.is_shutdown(): - # Initialize the low-level drivers (don't list the debug drivers) - # Scan for Crazyflies and use the first one found rospy.loginfo("Scanning interfaces for Crazyflies...") available=[] @@ -127,7 +122,10 @@ if __name__ == '__main__': #TODO: load address from parameters cf_client = PPSRadioClient(available[0][0]) time.sleep(3.0) - #TODO: register action/subscriber/.. callback + #TODO: change publisher name if not correct + rospy.Subscriber("PPSClient/MotorCommand", MotorCommand, motorControlCallback) + rospy.Subscriber("PPSClient/AngleCommand", AngleCommand, angleControlCallback) + rospy.Subscriber("PPSClient/RateCommand", RateCommand, rateControlCallback) rospy.spin() else: diff --git a/pps_ws/src/d_fall_pps/msg/AngleControl.msg b/pps_ws/src/d_fall_pps/msg/AngleCommand.msg similarity index 100% rename from pps_ws/src/d_fall_pps/msg/AngleControl.msg rename to pps_ws/src/d_fall_pps/msg/AngleCommand.msg diff --git a/pps_ws/src/d_fall_pps/msg/MotorControl.msg b/pps_ws/src/d_fall_pps/msg/MotorCommand.msg similarity index 100% rename from pps_ws/src/d_fall_pps/msg/MotorControl.msg rename to pps_ws/src/d_fall_pps/msg/MotorCommand.msg diff --git a/pps_ws/src/d_fall_pps/msg/RateControl.msg b/pps_ws/src/d_fall_pps/msg/RateCommand.msg similarity index 100% rename from pps_ws/src/d_fall_pps/msg/RateControl.msg rename to pps_ws/src/d_fall_pps/msg/RateCommand.msg diff --git a/pps_ws/src/d_fall_pps/srv/AngleController.srv b/pps_ws/src/d_fall_pps/srv/AngleController.srv index 7155b47db7c5198f5eeb80a0158b127bf24a46a6..8c896c49a0e08b7ee9f69ff5af91c459d79ae630 100644 --- a/pps_ws/src/d_fall_pps/srv/AngleController.srv +++ b/pps_ws/src/d_fall_pps/srv/AngleController.srv @@ -1,4 +1,4 @@ ViconData crazyflieLocation Setpoint setpoint --- -AngleControl controlOutput +AngleCommand controlOutput diff --git a/pps_ws/src/d_fall_pps/srv/MotorController.srv b/pps_ws/src/d_fall_pps/srv/MotorController.srv index 73167d624648d9e9a6b340b811d95f481005fb66..363b6d3c685fa631509d20263eb4f864f6c65f5b 100644 --- a/pps_ws/src/d_fall_pps/srv/MotorController.srv +++ b/pps_ws/src/d_fall_pps/srv/MotorController.srv @@ -1,4 +1,4 @@ ViconData crazyflieLocation Setpoint setpoint --- -MotorControl controlOutput +MotorCommand controlOutput diff --git a/pps_ws/src/d_fall_pps/srv/RateController.srv b/pps_ws/src/d_fall_pps/srv/RateController.srv index 51e8ceea6cf134b5c26d1071a692c0444eb96593..96469641221aa0aa5f2caa41f1c4aafcb78aa45f 100644 --- a/pps_ws/src/d_fall_pps/srv/RateController.srv +++ b/pps_ws/src/d_fall_pps/srv/RateController.srv @@ -1,4 +1,4 @@ ViconData crazyflieLocation Setpoint setpoint --- -RateControl controlOutput +RateCommand controlOutput