[ros-users] problem about setting private parameters of rosl…

Top Page
Attachments:
Message as email
+ (text/plain)
+ (text/html)
+ p3robot_tele_key.cpp (text/x-c++src)
+ teleop_keyboard.launch (application/octet-stream)
Delete this message
Reply to this message
Author: User discussions
Date:  
To: ros-users
Subject: [ros-users] problem about setting private parameters of roslaunch
Hi,

Recently, I am learning roslaunch order, and I have some problem with it.
First, I can drive the robot around manually in simulation using the
keyboard when I type roslaunch p3robot teleop_keyboard.launch. But when I
run roslaunch p3robot teleop_keyboard.launch in the real robot, the robot
can't response. In the file of teleop_keyboard.launch, I set three private
parameters. The src of my code and the .launch file are in the accessory.
What is the matter? Why the keyboard can control the simulation robot but
can't control the real robot with the same codes?
Or there is some problem with my .launch file? Thank you in advance!
--
Eileen
TJ University of Shang Hai
#include <ros/ros.h>
#include "geometry_msgs/Twist.h"
#include <signal.h>
#include <termios.h>
#include <stdio.h>

#define KEYCODE_R 0x43
#define KEYCODE_L 0x44
#define KEYCODE_U 0x41
#define KEYCODE_D 0x42
#define KEYCODE_Q 0x71

class TeleopP3Keyboard
{
private:
double fspeed;
double bspeed;
double rspeed;
geometry_msgs::Twist cmd;

ros::NodeHandle n_;
ros::Publisher vel_pub_;

public:
  void init()
  {
    cmd.linear.x = cmd.linear.y = cmd.angular.z = 0;


    vel_pub_ = n_.advertise<geometry_msgs::Twist>("cmd_vel",1);


    ros::NodeHandle n_private("~");
    n_private.param("fspeed",fspeed,0.5);
    n_private.param("bspeed",bspeed,0.5);
    n_private.param("rspeed",rspeed,0.5);
  }


~TeleopP3Keyboard() {}
void keyboardLoop();
};

int kfd = 0;
struct termios cooked, raw;

void quit(int sig)
{
tcsetattr(kfd, TCSANOW, &cooked);
exit(0);
}

int main(int argc, char** argv)
{
ros::init(argc, argv, "p3robot_tele_key");

TeleopP3Keyboard tpk;
tpk.init();

signal(SIGINT,quit);

tpk.keyboardLoop();

return(0);
}

void TeleopP3Keyboard::keyboardLoop()
{
char c;
bool dirty=false;

// get the console in raw mode
tcgetattr(kfd,&cooked);
memcpy(&raw, &cooked, sizeof(struct termios));
raw.c_lflag &=~ (ICANON | ECHO);
//setting a new line, then end of file
raw.c_cc[VEOL] = 1;
raw.c_cc[VEOF] = 2;
tcsetattr(kfd, TCSANOW, &raw);

  puts("Reading from keyboard");
  puts("---------------------------");
  puts("Use arrow keys to move the robot.");
  puts("Up Arrow: Forward     Down Arrow: Backward");
  puts("Left Arrow: Turn left     Right Arrow: Turn right");
  puts("Space: Stop     Q: quit");
  puts("---------------------------");


  while(ros::ok())
  {
    // get the next event from the keyboard  
    if(read(kfd, &c, 1) < 0)
    {
      perror("read():");
      exit(-1);
    }
    cmd.linear.x = cmd.linear.y = cmd.angular.z = 0;



  switch(c)
  {
    case KEYCODE_L:
      ROS_DEBUG("LEFT");
      cmd.angular.z = rspeed;
      cmd.linear.x = 0;
      cmd.linear.z = 0;
      dirty = true;
      break;
    case KEYCODE_R:
      ROS_DEBUG("RIGHT");
      cmd.angular.z = -rspeed;
      cmd.linear.x = 0;
      cmd.linear.z = 0;
      dirty = true;
      break;
    case KEYCODE_U:
      ROS_DEBUG("UP");
      fspeed += 10;
      bspeed = 20;
      cmd.linear.x = cmd.linear.y = fspeed;
      cmd.linear.z = 1;
      dirty = true;
      break;
    case KEYCODE_D:
      ROS_DEBUG("DOWN");
      fspeed = 20;
      bspeed += 10;
      cmd.linear.x = cmd.linear.y = -bspeed;
      cmd.linear.z = 1;
      dirty = true;
      break;
    case ' ':
      ROS_DEBUG("Stop");
      fspeed = bspeed = 20;
      cmd.linear.x = cmd.linear.y = 0;
      cmd.linear.z = 1;
      dirty = true;
      break;
    case VINTR: // Ctrl-C
    case KEYCODE_Q:
      tcsetattr(kfd, TCSANOW, &cooked);
      ros::shutdown();
      break;
    }


    if(dirty ==true)
    {
      vel_pub_.publish(cmd);    
      dirty=false;
    }


}
}