BLUESINK / Mbed 2 deprecated s-rov-firmware

Dependencies:   mbed pca9685 ros_lib_kinetic ads1015

main.cpp

Committer:
YJ_Kim
Date:
2017-01-16
Revision:
1:2062e7a67afd
Parent:
0:75ecba0f12ed
Child:
2:666847c29d89

File content as of revision 1:2062e7a67afd:

#include "mbed.h"
#include <ros.h>
#include <std_msgs/Float32.h>
#include <pca9685/pca9685.h>

class NewHardware : public MbedHardware{
    public:
    NewHardware():MbedHardware(PA_9, PA_10, 57600){};    
};
ros::NodeHandle_<NewHardware> nh;

I2C i2c(PB_11, PB_10);        // sda, scl
PCA9685 pwm(0x40, i2c, 50); 

void messageCb(const std_msgs::Float32& angle){
    pwm.set_servo_angle(CH_6, angle.data);
}

ros::Subscriber<std_msgs::Float32> sub("servo", &messageCb);

int main() {
    nh.initNode();
    nh.subscribe(sub);
    pwm.init();
    
    while (1) {
        nh.spinOnce();
        wait_ms(1);     
    }
}