def __init__(self): rospy.init_node('clearpath_base') self.port = rospy.get_param('~port', '') self.cmd_fill = rospy.get_param('~cmd_fill', True) if self.port != '': # Serial port rospy.loginfo("Using port %s", self.port) self.horizon = Horizon(transport=transports.Serial, transport_args={'port': self.port}) else: # Not specified. Autodetect. rospy.loginfo("Using port autodetection") self.horizon = Horizon(transport=transports.Serial.autodetect) announce_pub = rospy.Publisher('/clearpath/announce/robots', String, latch=True) announce_pub.publish(rospy.get_namespace()) self.freq_pub = rospy.Publisher('cmd_freq', Float32, latch=True) self.cmd_sub = rospy.Subscriber("cmd_vel", Twist, self.cmd_vel_handler) self.cmd_msg = Twist() self.cmd_time = rospy.Time.now() self.cmd_event = Event()
# exact serial data transports.logger.propagate = True transports.logger.setLevel(logging.WARNING) rospy.init_node('horizon_robot') # Instantiate Horizon PORT = rospy.get_param('~port', '') if PORT != '': # Serial port specified. print "Using specified port: %s " % PORT horizon = Horizon(transport = transports.HorizonTransport_Serial, transport_args = { 'port': PORT }, rec_timeout = 5000, send_timeout = 200, store_timeout = 10000) else: # Not specified. Autodetect. print "Using Serial Autodetect." horizon = Horizon(rec_timeout = 5000, send_timeout = 200, store_timeout = 10000) horizon.open() announce_pub = rospy.Publisher('/clearpath/announce', Announce, latch=True) announce_pub.publish(action="new_robot", topic=os.getenv("ROS_NAMESPACE", "")); data.DataReceiver(horizon) VELOCITY_CONTROL = int(rospy.get_param('~velocity_control', '0')) # bool OUTPUT_CONTROL = int(rospy.get_param('~output_control', '0')) # bool
#!/usr/bin/python """ Contest code for "Robotem Rovne (RR)" (Robot go Straight!) - taken from original example of Clearpath Robotics """ from clearpath.horizon import Horizon from clearpath.horizon.transports import Serial import time horizon = Horizon(transport=Serial, transport_args={'port':'/dev/ttyUSB1'}) #horizon = Horizon() horizon.open() def status_handler(code, payload, timestamp): print(payload.print_format()) #horizon.add_handler(status_handler, request = 'system_status') #horizon.request_system_status(subscription = 1) for i in range(1, 3): left_percent = right_percent = i * 10 horizon.set_differential_output(left_percent, right_percent) time.sleep(0.5) while True: horizon.set_differential_output(30, 33) time.sleep(0.5) time.sleep(1)