]> defiant.homedns.org Git - ros_roboint.git/blobdiff - src/libft_adapter.cpp
Migration to ros control (diff_drive_controller)
[ros_roboint.git] / src / libft_adapter.cpp
index 24fa1c474f420f7fce679338a5036d5a4c7d9ca0..63d710dcd063a1bd29d89d88d91a8cdb5aa99e15 100644 (file)
@@ -8,8 +8,8 @@
 
 
 static FT_TRANSFER_AREA *transfer_area = NULL;
-static char pwm[8] = {0};
-static char pwm_next[8] = {0};
+static int8_t pwm[8] = {0};
+static int8_t pwm_next[8] = {0};
 static pthread_mutex_t pwm_mutex = PTHREAD_MUTEX_INITIALIZER;
 
 void cb_set_output(const ::roboint::OutputConstPtr& msg) {
@@ -93,13 +93,14 @@ int main(int argc, char **argv)
         * than we can send them, the number here specifies how many messages to
         * buffer up before throwing some away.
         */
-       ros::Publisher chatter_pub = n.advertise<roboint::Inputs>("ft/get_inputs", 10);
+       ros::Publisher pub_inputs = n.advertise<roboint::Inputs>("ft/get_inputs", 10);
        ros::Rate loop_rate(100);
 
        while(ros::ok()) {
                roboint::Inputs msg;
 
                pthread_mutex_lock(&pwm_mutex);
+               msg.header.stamp = ros::Time::now();
                sem_wait(&hFt->lock);
                for (int i=0; i<=7; i++) {
                        msg.input[i] = (transfer_area->E_Main & (1<<i)) >> i;
@@ -131,7 +132,7 @@ int main(int argc, char **argv)
                 * given as a template parameter to the advertise<>() call, as was done
                 * in the constructor above.
                 */
-               chatter_pub.publish(msg);
+               pub_inputs.publish(msg);
 
                /**
                 * ros::spin() will enter a loop, pumping callbacks.  With this version, all