Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #include <ros/ros.h>
00039 #include <tf/transform_broadcaster.h>
00040 #include <nav_msgs/Odometry.h>
00041 #include <geometry_msgs/Twist.h>
00042
00043 #include "RobChair.h"
00044
00045 RobChair robot;
00046
00047 void cmdVelReceived(const geometry_msgs::Twist::ConstPtr& cmd_vel)
00048 {
00049 robot.setVelocities(cmd_vel->linear.x, cmd_vel->angular.z);
00050 }
00051
00052
00053 int main(int argc, char** argv)
00054 {
00055 ros::init(argc, argv, "robchair_node");
00056
00057 ROS_INFO("RobChair for ROS");
00058
00059 ros::NodeHandle n;
00060 ros::NodeHandle pn("~");
00061
00062 tf::TransformBroadcaster odom_broadcaster;
00063
00064 ros::Publisher odom_pub = n.advertise<nav_msgs::Odometry>("/odom", 50);
00065 ros::Subscriber cmd_vel_sub = n.subscribe<geometry_msgs::Twist>("/cmd_vel", 10, cmdVelReceived);
00066
00067 ros::Publisher tx_pub = n.advertise<can_msgs::CANFrame>("/can_bus_tx", 10);
00068 ros::Subscriber rx_sub = n.subscribe<can_msgs::CANFrame>("/can_bus_rx", 10, &RobChair::receivedCANFrame, &robot);
00069
00070
00071
00072 double kp, ki;
00073 if(pn.getParam("kp", kp) && pn.getParam("ki", ki))
00074 {
00075 ROS_INFO("RobChair -- Setting new PI gains.");
00076 robot.initializeRobChair(&tx_pub, kp, ki);
00077 }
00078
00079 else
00080 {
00081 robot.initializeRobChair(&tx_pub);
00082 }
00083
00084 ros::Time current_time;
00085
00086 ros::Rate r(50.0);
00087 while(n.ok())
00088 {
00089 current_time = ros::Time::now();
00090
00091 float odom_x = robot.getPositionX();
00092 float odom_y = robot.getPositionY();
00093 float odom_yaw = robot.getYaw();
00094
00095
00096 geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(odom_yaw);
00097
00098
00099 geometry_msgs::TransformStamped odom_trans;
00100 odom_trans.header.stamp = current_time;
00101 odom_trans.header.frame_id = "/odom";
00102 odom_trans.child_frame_id = "/base_link";
00103
00104 odom_trans.transform.translation.x = odom_x;
00105 odom_trans.transform.translation.y = odom_y;
00106 odom_trans.transform.rotation = odom_quat;
00107
00108
00109 odom_broadcaster.sendTransform(odom_trans);
00110
00111
00112 nav_msgs::Odometry odom;
00113 odom.header.stamp = current_time;
00114 odom.header.frame_id = "/odom";
00115
00116
00117 odom.pose.pose.position.x = odom_x;
00118 odom.pose.pose.position.y = odom_y;
00119 odom.pose.pose.orientation = odom_quat;
00120
00121
00122 odom.child_frame_id = "/base_link";
00123 odom.twist.twist.linear.x = robot.getLinearVelocity();
00124 odom.twist.twist.angular.z = robot.getAngularVelocity();
00125
00126
00127 odom_pub.publish(odom);
00128
00129 ros::spinOnce();
00130 r.sleep();
00131 }
00132
00133 return 0;
00134 }
00135
00136