RobotThread.cpp
Go to the documentation of this file.
00001 #include "RobotThread.h"
00002 
00003 namespace server {
00004 RobotThread::RobotThread(int argc, char** pArgv)
00005     :   m_Init_argc(argc),
00006         m_pInit_argv(pArgv)
00007 {}
00008 
00009 RobotThread::~RobotThread()
00010 {
00011     if (ros::isStarted())
00012     {
00013         ros::shutdown();
00014         ros::waitForShutdown();
00015     }//end if
00016 
00017     wait();
00018 }//end destructor
00019 
00020 bool RobotThread::init()
00021 {
00022     ros::init(m_Init_argc, m_pInit_argv, "tcp_command");
00023 
00024     if (!ros::master::check())
00025         return false;//do not start without ros.
00026 
00027     ros::start();
00028     ros::Time::init();
00029     ros::NodeHandle nh;
00030     //rostopic pub p2os_driver/MotorState cmd_motor_state -- 1.0
00031     cmd_publisher = nh.advertise<std_msgs::String>("/tcp_cmd", 1000);
00032     sim_velocity  = nh.advertise<geometry_msgs::Twist>("/cmd_vel", 100);
00033     pose_listener = nh.subscribe("/pose", 10, &RobotThread::callback, this);
00034     scan_listener = nh.subscribe("/scan", 1000, &RobotThread::scanCallBack, this);
00035     start();
00036     return true;
00037 }//set up the ros toys.
00038 
00039 void RobotThread::callback(nav_msgs::Odometry msg)
00040 {
00041     m_xPos = msg.pose.pose.position.x;
00042     m_yPos = msg.pose.pose.position.y;
00043     m_aPos = msg.pose.pose.orientation.w;
00044 
00045     ROS_INFO("Pose: (%f, %f, %f)", m_xPos, m_yPos, m_aPos);
00046 }//callback method to update the robot's position.
00047 
00048 void RobotThread::scanCallBack(sensor_msgs::LaserScan scan)
00049 {
00050     m_maxRange = scan.range_max;
00051     m_minRange = scan.range_min;
00052 
00053     for (unsigned int x = 0; x < scan.ranges.size(); x++)
00054         ranges.push_back(ranges.at(x));
00055 }//callback method for updating the laser scan data.
00056 
00057 void RobotThread::goToXYZ(geometry_msgs::Point goTo)
00058 {
00059     MoveBaseClient ac("move_base", true);
00060 
00061     while(!ac.waitForServer(ros::Duration(5.0))){
00062       ROS_INFO("Waiting for the move_base action server to come up");
00063     }
00064 
00065     move_base_msgs::MoveBaseGoal goal;
00066 
00067     //we'll send a goal to the robot to move 1 meter forward
00068     goal.target_pose.header.frame_id = "base_link";
00069     goal.target_pose.header.stamp = ros::Time::now();
00070 
00071     goal.target_pose.pose.position.x = goTo.x;
00072     goal.target_pose.pose.position.y = goTo.y;
00073     goal.target_pose.pose.orientation.w = goTo.z; // the angle will be on z.
00074 
00075     ROS_INFO("Sending goal");
00076     ac.sendGoal(goal);
00077 
00078     ac.waitForResult();
00079 
00080     if(ac.getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
00081       ROS_INFO("Hooray, the base moved 1 meter forward");
00082     else
00083       ROS_INFO("The base failed to move forward 1 meter for some reason");
00084 }//go to pose
00085 
00086 void RobotThread::run()
00087 {
00088     ros::Rate loop_rate(1);
00089     command = "empty";
00090     while (ros::ok())
00091     {
00092         std_msgs::String msg;
00093         std::stringstream ss;
00094         ss << command.toStdString();
00095 
00096         msg.data = ss.str();
00097 
00098         geometry_msgs::Twist cmd_msg;
00099         cmd_msg.linear.x = m_speed;
00100         cmd_msg.angular.z = m_angle;
00101 
00102         cmd_publisher.publish(msg);
00103         sim_velocity.publish(cmd_msg);
00104         ros::spinOnce();
00105         loop_rate.sleep();
00106     }//do ros things.
00107 }
00108 
00109 void RobotThread::SetSpeed(double speed, double angle)
00110 {
00111     ROS_INFO("SetSpeed recieved)");
00112     m_speed = speed;
00113     m_angle = angle;
00114     //rostopic pub -1 /turtle1/command_velocity turtlesim/Velocity  --2.0 --0.0
00115 }//set the speed of the robot.
00116 
00117 void RobotThread::setCommand(QString cmd)
00118 {
00119     command = cmd;
00120 }//get a command from another thread.
00121 
00122 void RobotThread::setPose(QList<double> to_set)
00123 {
00124     if (to_set.size() > 1)
00125     {
00126         m_xPos = to_set.at(0);//x coordinate
00127         m_yPos = to_set.at(1);//y coordinate
00128     }//end if
00129 }//end void
00130 
00131 double RobotThread::getXSpeed(){ return m_speed; }
00132 double RobotThread::getASpeed(){ return m_angle; }
00133 
00134 double RobotThread::getXPos(){ return m_xPos; }
00135 double RobotThread::getYPos(){ return m_yPos; }
00136 double RobotThread::getAPos(){ return m_aPos; }
00137 }//end namespace


tcp_command
Author(s): Hunter Allen
autogenerated on Mon Oct 6 2014 08:35:12