ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

How do I run cpp in a launch file?

asked 2018-12-03 21:53:06 -0500

Hyoungmin gravatar image

updated 2018-12-03 22:28:29 -0500

So I got this code so far:

<launch>

<group ns="turtlesim1">
<node pkg="turtlesim" name="sim" type="turtlesim_node"/>
</group>

<group ns="turtlesim2">
<node pkg="turtlesim" name="sim" type="turtlesim_node"/>
</group>

<node pkg="turtlesim" name="mimic" type="mimic">
<remap from="input" to="turtlesim1/turtle1"/>
<remap from="output" to="turtlesim2/turtle1"/>
</node>

<node pkg="turtlesim" name="teleop" type="turtle_teleop_key">
  <remap from="/turtle1/cmd_vel" to="/turtlesim1/turtle1/cmd_vel"/>
</node>

</launch>

and this cpp code :

#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 TeleopTurtle
{
public:
  TeleopTurtle();
  void keyLoop();

private:


  ros::NodeHandle nh_;
  double linear_, angular_, l_scale_, a_scale_;
  ros::Publisher twist_pub_;

};

TeleopTurtle::TeleopTurtle():
  linear_(0),
  angular_(0),
  l_scale_(2.0),
  a_scale_(2.0)
{
  nh_.param("scale_angular", a_scale_, a_scale_);
  nh_.param("scale_linear", l_scale_, l_scale_);

  twist_pub_ = nh_.advertise<geometry_msgs::Twist>("turtle1/cmd_vel", 1);
}

int kfd = 0;
struct termios cooked, raw;

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


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

  signal(SIGINT,quit);

  teleop_turtle.keyLoop();

  return(0);
}


void TeleopTurtle::keyLoop()
{
  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 turtle.");


  for(;;)
  {
    // get the next event from the keyboard  
    if(read(kfd, &c, 1) < 0)
    {
      perror("read():");
      exit(-1);
    }

    linear_=angular_=0;
    ROS_DEBUG("value: 0x%02X\n", c);

    switch(c)
    {
      case KEYCODE_L:
        ROS_DEBUG("LEFT");
        angular_ = -1.0;
        dirty = true;
        break;
      case KEYCODE_R:
        ROS_DEBUG("RIGHT");
        angular_ = 1.0;
        dirty = true;
        break;
      case KEYCODE_U:
        ROS_DEBUG("UP");
        linear_ = -1.0;
        dirty = true;
        break;
      case KEYCODE_D:
        ROS_DEBUG("DOWN");
        linear_ = 1.0;
        dirty = true;
        break;
    }


    geometry_msgs::Twist twist;
    twist.angular.z = a_scale_*angular_;
    twist.linear.x = l_scale_*linear_;
    if(dirty ==true)
    {
      twist_pub_.publish(twist);    
      dirty=false;
    }
  }


  return;
}

the teleop.cpp has been modded from original code so that the turtle moves and rotates in opposite direction from its original code.

However, I don't know how to implement this cpp code into the launch file so that turtlesim2 follows this code, while turtlesim1 follows the original code.

If anyone can help me out it would be greatly appreciated.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
2

answered 2018-12-03 22:44:24 -0500

Hamid Didari gravatar image

updated 2018-12-03 22:46:34 -0500

hi
first you need to creak pkg in your work space and compile the code and create node then you can use this launch file

<launch>

<group ns="turtlesim1">
<node pkg="turtlesim" name="sim" type="turtlesim_node"/>
</group>

<group ns="turtlesim2">
<node pkg="turtlesim" name="sim" type="turtlesim_node"/>
</group>

<node pkg="turtlesim" name="mimic" type="mimic">
<remap from="input" to="turtlesim1/turtle1"/>
<remap from="output" to="turtlesim2/turtle1"/>
</node>

<node pkg="turtlesim" name="teleop" type="turtle_teleop_key">
  <remap from="/turtle1/cmd_vel" to="/turtlesim1/turtle1/cmd_vel"/>
</node>

<node pkg="your_pkg" name="your-name" type="your type">//add this part
  <remap from="/turtle2/cmd_vel" to="/turtlesim2/turtle1/cmd_vel"/>
</node>
</launch>
edit flag offensive delete link more

Comments

Hey,

So I tried

<node pkg="beginner_tutorials" name="teleop2" type="teleop.cpp">
<remap from="/turtle2/cmd_vel" to="/turtlesim2/turtle1/cmd_vel"/>
</node>

but it gives me

Hyoungmin gravatar image Hyoungmin  ( 2018-12-03 22:50:46 -0500 )edit

but it gives me

ERROR: cannot launch node of type [beginner_tutorial/telop.cpp]: beginner_tutorial
ROS path [0]=/opt/ros/kinetic/share/ros
ROS path [1]=/home/username/catkin_ws/src
ROS path [2]=/opt/ros/kinetic/share

I don't know what I'm doing wrong...

Hyoungmin gravatar image Hyoungmin  ( 2018-12-03 22:51:06 -0500 )edit

can you run your node with rosrun?

Hamid Didari gravatar image Hamid Didari  ( 2018-12-04 00:42:29 -0500 )edit

no it won't, and I have no idea how to make it run...

Hyoungmin gravatar image Hyoungmin  ( 2018-12-04 00:59:16 -0500 )edit
1

You have to compile the cpp source file into an executable binary before it can be used. Please look at he tutorials for cpp nodes, they explain all of this

PeteBlackerThe3rd gravatar image PeteBlackerThe3rd  ( 2018-12-04 02:06:20 -0500 )edit

I shall do so. Thank you for the reference.

Hyoungmin gravatar image Hyoungmin  ( 2018-12-04 02:26:22 -0500 )edit

In addition to compiling the source code I had to change the type in the following line in the first comment by dropping the .cpp extension:

From

<node pkg="beginner_tutorials" name="teleop2" type="teleop.cpp">

to

<node pkg="beginner_tutorials" name="teleop2" type="teleop">

Caleb gravatar image Caleb  ( 2020-08-18 13:34:38 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2018-12-03 21:53:06 -0500

Seen: 7,563 times

Last updated: Dec 03 '18