X-Git-Url: https://defiant.homedns.org/gitweb/?a=blobdiff_plain;ds=sidebyside;f=src%2Flibft_adapter.cpp;h=63d710dcd063a1bd29d89d88d91a8cdb5aa99e15;hb=e2df79c17569d45bd959aec083c5fd6e72ca960b;hp=7df56b45c620c4e2b567cdc13404d7258ef74de1;hpb=469b75c3effbb9d108adca56adf81b0c77a0b2e2;p=ros_roboint.git diff --git a/src/libft_adapter.cpp b/src/libft_adapter.cpp index 7df56b4..63d710d 100644 --- a/src/libft_adapter.cpp +++ b/src/libft_adapter.cpp @@ -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,7 +93,7 @@ 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("ft/get_inputs", 10); + ros::Publisher pub_inputs = n.advertise("ft/get_inputs", 10); ros::Rate loop_rate(100); while(ros::ok()) { @@ -132,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