GithubHelp home page GithubHelp logo

ros-pwm-pca9685's Introduction

ROS driver for NXP Semiconductor PCA9685 I2C PWM chip

This is a ROS node for the PCA9685. The chip is notably used in the following products:

There should be no dependencies besides libi2c-dev.

Parameters:

  • device (string) -- the path to the i2c device. Default is /dev/i2c-1. Use i2cdetect in the i2c-tools package to find out which bus your device is on.
  • address (int) -- the i2c address of the PCA9685. Default is 0x40.
  • frequency (int) -- PWM frequency in Hz. Default is 1600.
  • timeout (list of ints) -- List of 16 integers corresponding to timeouts in milliseconds for each channel. If any particular channel is not updated in this time, that channel will be set to the corresponding value in timeout_value until another update is received. Defaults to [ 5000, 5000, ... ], i.e. each channel timeouts after 5 seconds if no updates are published.
  • timeout_value (list of ints) -- The value each channel will be set to upon timeout. Defaults to [ 0, 0, ... ], i.e. each channel is set to 0 upon timeout.
  • pwm_min (list of ints) -- The minimum PWM value for each channel. Defaults to [ 0, 0, ... ]. If a command lower than the minimum PWM value is issued, the PWM value will be set to param_min, with the exception of a -1 command, which designates no update (see below).
  • pwm_max (list of ints) -- The maximum PWM value for each channel. Defaults to [ 65535, 65535, ... ]. If a command larger than param_max is issued, the PWM value will be set to param_max.

Subscribers

  • command -- a Int32MultiArray containing exactly 16 values corresponding to the 16 PWM channels. For each value, specify -1 to make no update to a channel. Specify a value between 0 and 65535 inclusive to update the channel's PWM value. For example, {data: [32767, 0, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1]} will update channel 0 to a PWM of 50%, channel 1 to 0%, and make no updates to other channels.

Publishers

None.

Services

None.

Usage notes

With the Adafruit 16-channel servo breakout (or any other servo breakout)

The default I2C address is 0x40. A full servo range tyically corresponds to a PWM duty cycle of about 2800/65535 to 7600/65535 (NOT 0/65535 to 65535/65535), so make sure you publish updates according to the servo PWM range. You will also want to set the frequency parameter to 50 Hz for servos.

With the Adafruit Motor Driver HAT

The default I2C address is 0x60.

The PCA9685 generates PWM signals that are connected to two TB6612 dual motor driver chips, for a total of 4 motors. Three PCA9685 channels are connected to each motor, as described below, for a total of 4*3=12 channels wired to the motors. The 4 "extra" PWM pins (0, 1, 14, 15) are not connected to any motors are broken out on a separate header on the board.

Refer to the Toshiba TB6612FNG documentation for more info on the TB6612.

For each motor, there are 3 pins: PWM, IN1, and IN2.

  • PWM should be a PWM signal (0 to 65535) indicating the amount of power.
  • IN1 should be binary, i.e. set to 0 OR 65535, nothing in-between.
  • IN2 should be binary, i.e. set to 0 OR 65535, nothing in-between.
  • IN1 = 65535, IN2 = 65535: Brake
  • IN1 = 65535, IN2 = 0: Forward
  • IN1 = 0, IN2 = 65535: Reverse
  • IN1 = 0, IN2 = 0: High impedance (coast)

Motor channels

  • Motor1: PWM = channel 8, IN1 = channel 9, IN2 = channel 10
  • Motor2: PWM = channel 13, IN1 = channel 11, IN2 = channel 12
  • Motor3: PWM = channel 2, IN1 = channel 3, IN2 = channel 4
  • Motor4: PWM = channel 7, IN1 = channel 5, IN2 = channel 6

For example, to set motor 1 to forward at 50%, send {data: [-1, -1, -1, -1, -1, -1, -1, -1, 32767, 65535, 0, -1, -1, -1, -1, -1]}

Command Line Example: Again setting motor 1 to forward at 50%.

rostopic pub -1 /command std_msgs/Int32MultiArray -- {data:'[-1,-1,-1,-1,-1,-1,-1,-1,32767,65535,0,-1,-1,-1,-1,-1]'}	

Python Example: Again setting motor 1 to forward at 50%.

import rospy
from std_msgs.msg import Int32MultiArray
pub = rospy.Publisher('command', Int32MultiArray, queue_size=10)
rospy.init_node('your_node_name')
r = rospy.Rate(10) # 10hz
drive_motor_1=data=Int32MultiArray(data=[-1,-1,-1,-1,-1,-1,-1,-1,32767,65535,0,-1,-1,-1,-1,-1])
while not rospy.is_shutdown():
   pub.publish(drive_motor_1)
   r.sleep()

ros-pwm-pca9685's People

Contributors

dheera avatar odart avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

ros-pwm-pca9685's Issues

Segmentation Fault

Hi @dheera

I am pretty new to ROS and trying to build a RPi-Robot to learn it.
I have this PCA9685 based PWM board and I run ROS Melodic on Debian Buster and everything works fine (including a camera). The board has address 0x40 so the default parameters are probably correct.

libi2c-dev is installed and I try to start your node like this:

rosrun pwm_pca9685 pca9685_node

But it segfaults:

[ INFO] [1585099217.457893949]: initializing
[ INFO] [1585099217.477227357]: starting
Segmentation fault

(gdb) backtrace

#0  0x00016158 in pwm_pca9685::PCA9685Activity::set(unsigned char, unsigned short) ()
#1  0x00016ae0 in pwm_pca9685::PCA9685Activity::spinOnce() ()
#2  0x00015bd4 in main ()

Maybe you know why this happens or you can tell me how to properly debug it.

Why does motor run for so long?

Hi, I am very new to ROS, but I was able to compile the code and publish to my robot. I am just trying to simply move my motor, but it seems like I don't know how to control how long the motor runs for? I first want 2 motors to run, then the first only then the second only. I believe I also need to tell the motor to stop in between

Here is my code

#!/usr/bin/python3
import rospy, time
from std_msgs.msg import Int32MultiArray

class motor():
  def __init__(self):
    rospy.loginfo("Setting Up the Node...")
    self.pub = rospy.Publisher("command", Int32MultiArray, queue_size=10)
    rospy.init_node('motor_test')
    self.r = rospy.Rate(10)# 10hz
  def send_motor_msg(self):
    self.pub.publish(Int32MultiArray(data=[0, 0, 0, 0,0,0,0,0,0,0,0,0,0,0,0,0]))
    self.pub.publish(Int32MultiArray(data=[32717, 0, 32717, -1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1]))
    self.pub.publish(Int32MultiArray(data=[0, 0, 0, 0,0,0,0,0,0,0,0,0,0,0,0,0]))
    self.pub.publish(Int32MultiArray(data=[32717, 0, 0, -1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1]))
    self.pub.publish(Int32MultiArray(data=[0, 0, 0, 0,0,0,0,0,0,0,0,0,0,0,0,0]))
    self.pub.publish(Int32MultiArray(data=[0, 0, 32717, -1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1]))
if __name__=="__main__":
  m = motor()
  while not rospy.is_shutdown():
    m.send_motor_msg()
    m.r.sleep()

How can I control it such that I can tell the robot how long to run a motor?

How do I actually make this a ROS node?

Showing my colors here, but I'm new to ROS. I have ROS setup and running, receiving inputs from a joy_node I've configured that's taking in inputs from an Xbox One S controller (bluetooth). What I'd like to do is relay those inputs to this PCA9685 node to drive two motors and a steering servo.

I bought a WaveShare JetRacer kit that comes with a "JetCard" distro/jupyter notebook that's kind of watered down and had a lot of functions that weren't working, so I decided to just load JetPack and try some stuff for myself. There's a battery+oled+SCL/SDA "hat" that comes with the JetRacer which has most stuff being driven over i2c. I've been able to drive the motors and steering rack using the servokit and motorkit package from adafruit in a terminal just to test their functionality.

Where I'm running into a snag is trying to pull those "kits" into ROS, which is where I found you! I just need to figure out how to turn this into a node so I can start testing things from ROS.

How to properly pass parameters?

I have been trying to pass parameters to the node and cant seem to figure out what is going on. Here is what I tried:
rosrun pwm_pca9685 pca9685_node timeout:=[100,100,100,100,100,100,100,100,100,100,100,100,100,100,100,100] but it still runs for 5 seconds. I have also tried rosrun pwm_pca9685 pca9685_node _timeout:=[100,100,100,100,100,100,100,100,100,100,100,100,100,100,100,100] and the same thing. Any advice?

what about ros2?

Will this solution work for ros2 on catkin too? I see colcon dependencies in CMakeLists.txt which I guess points to old ros (version 1).

Moving at start-up even with no commad on Jetracer

Hi,

Thanks for the code. I am using a Waveshare jetracer with its schematic in driving motos and servos in this link.
Despite the settings of this hardware, the motors start spining and stop once I run the node directly. I am a bit confused since the default of this node should hold everything to 0%?

Robot doing random movements

Hi dheera,

I'm trying to use your driver node on my project with the PCA9685 and a raspberry connected to it by i2c. The i2c works because I used it with the servokit library and works really fine. What is happening is that when your ros is running in the raspberry pi the robot start to make random movements that has not send and without sending any command. I don't know why is this working like that. I don't know if it's something important but I'm working with the roboti arm sainsmart 6dof.

I also tried to publish a command in the /command topic but when I do it it latched, in the /command is received but no motor is working. When I use the rqt_graph I get this image and I don't understand what is doing. Can you give me some feedback ? I send you also the rqt_graph

WhatsApp Image 2021-01-15 at 20 14 10

[ERROR] i2c device open failed

Hi everybody,

I try to launch the node with the command :
rosrun pwm_pca9685 pca9685_node
But I keep have the same error : i2c device open failed
My I2C port works correctly, the command sudo i2cdetect -y 1 sees the board

Do you have any idea of the source of the problem ?

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    ๐Ÿ–– Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. ๐Ÿ“Š๐Ÿ“ˆ๐ŸŽ‰

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google โค๏ธ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.