diff --git a/config/omniwheels_config.yaml b/config/omniwheels_config.yaml index 7da006515acef2554deb51c55751b820bffc090c..8bd041b0ed8e426d55f8fbabc34b50501c3a35de 100644 --- a/config/omniwheels_config.yaml +++ b/config/omniwheels_config.yaml @@ -1,6 +1,6 @@ # configuration file for all the omniwheels -name: "omniwheel1" -id: 1 +name: "omniwheel2" +id: 2 channel: 90 # change to the correct one type: default position_offset: 0.11 # ofsset from crazyflie module to the cenyter of the omniwheels diff --git a/scripts/__pycache__/SimplePI.cpython-37.pyc b/scripts/__pycache__/SimplePI.cpython-37.pyc index 367ecb7e4cf6ad3b1c9d85960607279f4cfee9b2..d5c9c1aa044657e416993b72a44433c91525b1f6 100644 Binary files a/scripts/__pycache__/SimplePI.cpython-37.pyc and b/scripts/__pycache__/SimplePI.cpython-37.pyc differ diff --git a/scripts/omni_wheel_controller_node.py b/scripts/omni_wheel_controller_node.py index 8127a284f1048c518bba82a79ac1ba38198cf299..0ee957cb2c5326029d18312b10121d29086a4764 100755 --- a/scripts/omni_wheel_controller_node.py +++ b/scripts/omni_wheel_controller_node.py @@ -76,8 +76,8 @@ class omniWheelvelocityController: rospy.Subscriber("vel_cmd", Twist, self.velocityCommandCallback) # pose and velocity values ss = rospy.get_param("/name") - ss_pose = "/" + ss+"/pose"; - ss_vel= "/" + ss+"/vel"; + ss_pose = "pose"; + ss_vel= "vel"; rospy.Subscriber(ss_pose, Pose, self.poseCallback) rospy.Subscriber(ss_vel, Twist, self.velCallback) @@ -100,8 +100,6 @@ class omniWheelvelocityController: # main loop while not rospy.is_shutdown(): - - if self.vel_cmd_arrived == True and self.vel_callback_initiated == True and self.pose_callback_initiated==True: # compute motor values from velocity command roll, pitch,yaw = euler_from_quaternion(self._current_pose.orientation.x,self._current_pose.orientation.y,self._current_pose.orientation.z,self._current_pose.orientation.w)