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

How to use external c++ function in node main function

asked 2020-09-16 06:26:25 -0500

MjdKassem gravatar image

i have a package called "my_serial_example" in the source directory of this package i have a "receiveSerialData.cpp" which include the executable node and "TerminalCommand.h" and "TerminalCommand.cpp", like this:

TerminalCommand.h

    class Command
    {
        //Some #define
        private:
        public:
        //Some variable
        bool parseCommand(uint8_t _command);
        void initCommand();
    };

TerminalCommand.ccp

#include "TerminalCommand.h"
bool Command::parseCommand(uint8_t _receivedByte)
{
  //Some Operation
}

and in the "receiveSerialData.cpp"

#include"TerminalCommand.h"
Command myRecivedCommand;
int main (int argc, char** argv)
{
    ros::init(argc, argv, "receiveSerialData");
    ros::NodeHandle nh;
   bool x = myRecivedCommand.parseCommand;
}

when i am build the package "my_serial_example", i got this error

undefined reference to `Command::parseCommand(unsigned char)'

i think the problem in "CMakeLists.txt" file which look like:

cmake_minimum_required(VERSION 2.8.3)
project(my_serial_example)

find_package(catkin REQUIRED COMPONENTS
  roscpp
  serial
  std_msgs
  tf
  roslib
)
catkin_package(
  CATKIN_DEPENDS
    serial
    std_msgs
    roscpp
)
include_directories(
  ${catkin_INCLUDE_DIRS}
)
add_executable(receiveSerialData src/receiveSerialData.cpp)
target_link_libraries(receiveSerialData ${catkin_LIBRARIES})

have any solve please, how to link my function to my executable node thank

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
2

answered 2020-09-16 08:22:55 -0500

JackB gravatar image

updated 2020-09-16 15:47:53 -0500

In c++ the compiler really has two parts, the compiler and the linker. You need to explicitly tell the compiler everything that it needs to compile. In addition to that, you need to specify what it needs to link together. The product of the linker is the executable that can be run.

In your example here, you are instructing the machine to generate receiveSerialData and it is telling you, "hey where are the definitions to this code you told me I could use" (undefined reference to Command::parseCommand(unsigned char)'). There are two parts to that statement:

(1) "hey where are the definitions"- This means that you never told the linker where the compiled code used by receiveSerialData is actually located

(2) "code you told me I could use"- This part you did correctly by using the#include "TerminalCommand.h" preprocessor command. This gave your receiveSerialData the declarations to the class you wanted to use.

So you correctly told the program what code to expect with (2), BUT you never told it where to actually find the definition of this code (1).

In order to do correctly do this you need to tell the compiler to generate a library out of your terminalCommand.cpp. After where you declare you "include directories" in your CMake add this:

## Declare a C++ library 
add_library(TerminalCommand src/TerminalCommand.cpp)

At this point now you will have generated a compiled version of your code that can now be "linked" with other code like your executbale. To "link" this code to your executable which is the one that actually needs access to the content in the TeminalCommand library include it in your "target link" command like

## Link the library to the executable
target_link_libraries(receiveSerialData TerminalCommand ${catkin_LIBRARIES})

And that should be it, it will hopefully at least compile now, not saying that your code is right :) Here is a nice explanation from the broader C++ community explaining the issue in more detail link text

edit flag offensive delete link more

Comments

Did this answer help solve your problem? Or is something else wrong?

JackB gravatar image JackB  ( 2020-09-19 10:58:46 -0500 )edit

thank you, you fully solved my problem, as you mentioned, i have forget to Link the library to the executable

MjdKassem gravatar image MjdKassem  ( 2020-09-19 13:28:23 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2020-09-16 06:26:25 -0500

Seen: 473 times

Last updated: Sep 16 '20