Skip to content

Commit

Permalink
Change the msg name for motors
Browse files Browse the repository at this point in the history
  • Loading branch information
ryuichiueda committed Oct 14, 2016
1 parent d005c18 commit 73d3fd8
Show file tree
Hide file tree
Showing 5 changed files with 6 additions and 6 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Expand Up @@ -48,7 +48,7 @@ add_message_files(
FILES
LightSensorValues.msg
Switches.msg
LeftRightFreqs.msg
MotorFreqs.msg
)

# Generate services in the 'srv' folder
Expand Down
File renamed without changes.
4 changes: 2 additions & 2 deletions scripts/check_driver_io.py
Expand Up @@ -19,10 +19,10 @@ def switch_motors(onoff):
return False

def raw_control(left_hz,right_hz):
pub = rospy.Publisher('/raspimouse/motor_raw', LeftRightFreqs, queue_size=10)
pub = rospy.Publisher('/raspimouse/motor_raw', MotorFreqs, queue_size=10)

if not rospy.is_shutdown():
d = LeftRightFreqs()
d = MotorFreqs()
d.left = left_hz
d.right = right_hz
pub.publish(d)
Expand Down
4 changes: 2 additions & 2 deletions scripts/rtmotor.py
Expand Up @@ -3,7 +3,7 @@
import rospy
from raspimouse_ros.srv import PutMotorFreqs
from raspimouse_ros.srv import SwitchMotors
from raspimouse_ros.msg import LeftRightFreqs
from raspimouse_ros.msg import MotorFreqs
from std_msgs.msg import Bool

def callback_motor_sw(message):
Expand Down Expand Up @@ -49,7 +49,7 @@ def callback_put_freqs(message):

def listner():
rospy.init_node('rtmotor')
sub = rospy.Subscriber('motor_raw', LeftRightFreqs, callback_motor_raw)
sub = rospy.Subscriber('motor_raw', MotorFreqs, callback_motor_raw)
srv = rospy.Service('switch_motors', SwitchMotors, callback_motor_sw)
srv = rospy.Service('put_motor_freqs', PutMotorFreqs, callback_put_freqs)
rospy.spin()
Expand Down
2 changes: 1 addition & 1 deletion test/travis_test.bash
Expand Up @@ -5,7 +5,7 @@ sleep 20

#publishing
rostopic pub -1 /raspimouse/buzzer std_msgs/UInt16 -- 10
rostopic pub -1 /raspimouse/motor_raw raspimouse_ros/LeftRightFreqs '123' '456'
rostopic pub -1 /raspimouse/motor_raw raspimouse_ros/MotorFreqs '123' '456'

#service call
rosservice call /raspimouse/put_motor_freqs 'left: -300
Expand Down

0 comments on commit 73d3fd8

Please sign in to comment.