Esempio n. 1
0
def run_motor_using_with():
    with VESC(serial_port=serial_port) as motor:
        print("Firmware: ", motor.get_firmware_version())
        motor.set_duty_cycle(.02)

        # run motor and print out rpm for ~2 seconds
        for i in range(30):
            time.sleep(0.1)
            print(motor.get_measurements().rpm)
        motor.set_rpm(0)
Esempio n. 2
0
 def connectVESC(self):
     try:
         self.motor = VESC(serial_port=self.serial_port)
     except Exception as e:
         rospy.logwarn(
             "Opening serial failed during init! reconnecting %d times" %
             (self.errCount + 1))
         rospy.sleep(3)
         self.handleException(e)
         self.motor = self.connectVESC()
     self.errCount = 0
Esempio n. 3
0
def run_motor_as_object():
    motor = VESC(serial_port=serial_port)
    # print("Firmware: ", motor.get_firmware_version())

    # sweep servo through full range
    for i in range(100):
        time.sleep(0.0)
        motor.set_servo(i/100)

    # IMPORTANT: YOU MUST STOP THE HEARTBEAT IF IT IS RUNNING BEFORE IT GOES OUT OF SCOPE. Otherwise, it will not
    #            clean-up properly.
    motor.stop_heartbeat()
Esempio n. 4
0
def set_speed(speed, count):
    with VESC(serial_port=serial_port) as motor:
    
        if count == 0:
            return "Err"
        try:
            tacho = motor.set_duty_cycle(speed)

        except:
            count -= 1
            set_speed(speed, count)


        return
Esempio n. 5
0
def get_encoder_value(count):
    with VESC(serial_port=serial_port) as motor:
    
        if count == 0:
            return "Err"
        try:
            tacho = motor.get_measurements().tachometer
            print("hallsensor:",tacho)
        except:
            count -= 1
            get_encoder_value(count)


        return tacho
Esempio n. 6
0
def run_motor_using_with():
    with VESC(serial_port=serial_port) as motor:
    
        # for i in range(40):
        while True:
            #time.sleep(0.05)
            # print("rpm:",motor.get_measurements().rpm)
            try:
                response = motor.get_measurements().rpy_1
                print("hallsensor:",response)
            except:
                pass
            
            
            time.sleep(0.1)
Esempio n. 7
0
def run_motor_using_with():
    with VESC(serial_port=serial_port) as motor:
        # print("Firmware: ", motor.get_firmware_version())

        
        start_tacho = motor.get_measurements().tachometer
        print("hallsensor:",start_tacho)
        
        
        motor.set_duty_cycle(.02)
        start = time.time()

        # print("Getting values takes ", stop-start, "seconds.")
        # run motor and print out rpm for ~2 seconds
        for i in range(20):
            #time.sleep(0.05)
            # print("rpm:",motor.get_measurements().rpm)
            response_tacho = motor.get_measurements().tachometer
            print("hallsensor:",response_tacho)
            
            stop = time.time()
            if start_tacho != response_tacho:
                print("response time:",stop-start)
            time.sleep(0.02)

        motor.set_rpm(0)
        motor.set_duty_cycle(-.02)
        print("rpm:",motor.get_measurements().rpm)
        print("hallsensor:",motor.get_measurements().tachometer)
        time.sleep(2)
        motor.set_rpm(-500)
        time.sleep(2)
        print("rpm:",motor.get_measurements().rpm)
        motor.set_rpm(500)
        time.sleep(2)
        motor.set_rpm(0)
Esempio n. 8
0
def time_get_values():
    with VESC(serial_port=serial_port) as motor:
        start = time.time()
        motor.get_measurements()
        stop = time.time()
        print("Getting values takes ", stop-start, "seconds.")
Esempio n. 9
0
if __name__ == '__main__':

    rospy.init_node('vesc', anonymous=True)

    pub = rospy.Publisher('/vesc_feedback', vesc_feedback, queue_size=1)
    msg = vesc_feedback()

    rospy.Subscriber("/cmd_vel", Twist, cmd_velCallback)

    rospy.Subscriber("/joy_cmd", Twist, joy_cmdCallback)
    rospy.Subscriber("/joy", Joy, joyCallback)

    rate = rospy.Rate(20)

    motor = VESC(serial_port=serial_port)
    init_tacho = initialize(0)

    set_and_get_speed(0, 50, 10)
    rospy.sleep(0.05)

    while not rospy.is_shutdown():

        # print(time.time())
        # rospy.sleep(0.01)

        # current_tacho = set_and_get_speed(8, steer_cmd, 10)

        msg.tacho.data = set_and_get_speed(speed_cmd, steer_cmd,
                                           10) - init_tacho
        rospy.loginfo(msg.tacho.data)
Esempio n. 10
0
    def _initialize_rc_control(self, communication):
        """This function creates the properties to control the motor and steering.
        :param communication: either 'VESC_CONTROL' for using the VESC or 'ARDUINO_CONTROL' for using an ArduinoI2CBus

        * * *
        """

        if self.rc_control == self.VESC_CONTROL:
            self.gain_id = JetsonEV.VESC_CONTROL
            if communication == 'USB':
                try:
                    for dev in os.listdir('/dev/serial/by-id'):
                        if dev.find('ChibiOS') >= 0:
                            communication = '/dev/serial/by-id/' + dev
                except FileNotFoundError:
                    raise Exception(
                        'Unable to find VESC device. Check port and power.')
            try:
                self.vesc = VESC(serial_port=communication)
            except Exception as e:
                raise e

            self._set_servo_percent = self.vesc.set_servo

            def vesc_motor_duty(percentage):
                # percentage should be between -1 and 1
                self.vesc.set_duty_cycle(percentage)

            self._set_motor_duty = vesc_motor_duty
            self._speed_socket = SendSocket(tcp_port=JetsonEV.SPEED_PORT,
                                            tcp_ip=ip_address)
            self._output_sockets.append(self._speed_socket)
            new_conversion = speed_conversion * poles_on_motor  # poles in motor

            def set_motor_speed(new_speed):
                self.speed = new_speed * new_conversion
                self._speed_socket.send_data(self.speed)

            self.motor_speed_task = self.add_timed_task(
                calling_function=self.vesc.get_rpm,
                sampling_rate=20,
                forwarding_function=set_motor_speed,
                verbose=False)

        else:  # Use arduino
            self.gain_id = JetsonEV.ARDUINO_CONTROL
            self.arduino_devices = ArduinoI2CBus(communication)

            self.StWhl = self.arduino_devices.create_servo_dev(
                pin=JetsonEV.ARDUINO_CONFIG['steering_pin'])
            self.StWhl.attach()
            self._set_servo_percent = self.StWhl.write_percentage

            self.Motor = self.arduino_devices.create_servo_dev(
                pin=JetsonEV.ARDUINO_CONFIG['motor_pwm_pin'])
            self.Motor.attach()

            self._last_duty = [0]
            self._was_reversing = [False]

            # define function to handle a percentage from -1 to 1 and convert to regular ESC percentage
            def arduino_motor_duty(percentage):
                if percentage < 0 and self._last_duty[
                        0] >= 0 and not self._was_reversing[0]:
                    self.Motor.write_percentage(.1)
                    time.sleep(0.15)
                    self.Motor.write_percentage(.5)
                    self._current_duty = 0
                    time.sleep(0.1)
                    self._was_reversing[0] = True

                self._last_duty[0] = percentage

                if percentage >= 0:
                    if percentage > 0:
                        self._was_reversing[0] = False
                    percentage = 0.5 * percentage + 0.5  # convert to percent of pwm above 50 %
                else:
                    percentage = 0.5 - 0.5 * abs(percentage)

                self.Motor.write_percentage(percentage)

            self._set_motor_duty = arduino_motor_duty

            encoder = self.arduino_devices.create_BLDC_encoder_dev(
                pin_A=JetsonEV.ARDUINO_CONFIG['motor_pin_a'],
                pin_B=JetsonEV.ARDUINO_CONFIG['motor_pin_b'],
                pin_C=JetsonEV.ARDUINO_CONFIG['motor_pin_c'])

            self._speed_socket = SendSocket(tcp_port=JetsonEV.SPEED_PORT,
                                            tcp_ip=ip_address)
            self._output_sockets.append(self._speed_socket)

            def set_motor_speed(new_speed):
                self.speed = new_speed * speed_conversion
                self._speed_socket.send_data(self.speed)

            self.motor_encoder = self.add_timed_task(
                calling_function=encoder.get_speed,
                object_to_wrap=encoder,
                sampling_rate=20,
                forwarding_function=set_motor_speed,
                verbose=True)