robchair_node.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 *
00003 * Software License Agreement (BSD License)
00004 *
00005 *  Copyright (c) 2012, ISR University of Coimbra.
00006 *  All rights reserved.
00007 *
00008 *  Redistribution and use in source and binary forms, with or without
00009 *  modification, are permitted provided that the following conditions
00010 *  are met:
00011 *
00012 *   * Redistributions of source code must retain the above copyright
00013 *     notice, this list of conditions and the following disclaimer.
00014 *   * Redistributions in binary form must reproduce the above
00015 *     copyright notice, this list of conditions and the following
00016 *     disclaimer in the documentation and/or other materials provided
00017 *     with the distribution.
00018 *   * Neither the name of the ISR University of Coimbra nor the names of its
00019 *     contributors may be used to endorse or promote products derived
00020 *     from this software without specific prior written permission.
00021 *
00022 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 *  POSSIBILITY OF SUCH DAMAGE.
00034 *
00035 * Author: Gonçalo Cabrita on 28/05/2012
00036 *********************************************************************/
00037 
00038 #include <ros/ros.h>
00039 #include <tf/transform_broadcaster.h>
00040 #include <nav_msgs/Odometry.h>                  // odom
00041 #include <geometry_msgs/Twist.h>                // cmd_vel
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     // PI parameters...
00071     // If we defined Kp and Ki set them
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     // Otherwise go with default values
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                 // Since all odometry is 6DOF we'll need a quaternion created from yaw
00096                 geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(odom_yaw);
00097                 
00098                 // First, we'll publish the transform over tf
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                 // Send the transform
00109                 odom_broadcaster.sendTransform(odom_trans);
00110                 
00111                 // Next, we'll publish the odometry message over ROS
00112                 nav_msgs::Odometry odom;
00113                 odom.header.stamp = current_time;
00114                 odom.header.frame_id = "/odom";
00115                 
00116                 // Set the position
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                 // Set the velocity
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                 // Publish the message
00127                 odom_pub.publish(odom);
00128 
00129                 ros::spinOnce();
00130                 r.sleep();
00131         }
00132         
00133         return 0;
00134 }
00135 
00136 // EOF


robchair_driver
Author(s): Gonçalo Cabrita
autogenerated on Mon Jan 6 2014 11:26:14