Robotics StackExchange | Archived questions

CMakeLists.txt target_link_libraries is not linking my library

Its my same question with more details I have written code imu.cpp which is using ftdi library named libftd2xx. Code is given below

imu.cpp

  #include <ros/ros.h>
  #include <tf/transform_broadcaster.h>
  #include <nav_msgs/Odometry.h>
  #include <sensor_msgs/Imu.h>
   #include <stdio.h>
   #include <stdlib.h>
   #include <sys/time.h>
   #include <string.h>
   #include <unistd.h>
  #include <ftd2xx.h>
 using namespace std;
 int main(int argc, char** argv){
     ros::init(argc, argv, "First_node");

     ros::NodeHandle n;
      ros::Publisher imu_pub = n.advertise<sensor_msgs::Imu>("imu", 50);
     ros::Publisher odom_pub = n.advertise<nav_msgs::Odometry>("odom", 50);
    tf::TransformBroadcaster odom_broadcaster;
FT_STATUS   ftStatus;
FT_HANDLE   ftHandle;
DWORD BytesWritten;
DWORD EventDWord;
DWORD TxBytes;
DWORD RxBytes;
DWORD BytesReceived;
DWORD libraryVersion = 0;
int iport,len,i,direction=0,adjust;
unsigned char RxBuffer[30],outword[60];
int ch=1,c=0;
unsigned char TxBuffer13[]="\x4E\x45\x58\x90\x02\r\n"; // Set Mode 00 , 01,02
unsigned char TxBuffer[40]="\x4E\x45\x58",TxBuffer1[256]; // Contains data to write to device
unsigned char  data[40];
unsigned char TxBuffer16[]="\x4E\x45\x58\x9C\x00\x00\x02\x30\x01\x00\x00\x02\x30\x01\r\n"; // Set Position
unsigned char TxBufferA[]="\x4E\x45\x58\x9C\x00\x00\x00\x00\xFF\x00\x00\x00\x00\x01\r\n";
unsigned char TxBufferC[]="\x4E\x45\x58\x9C\x00\x00\x00\x00\x01\x00\x00\x00\x00\xFF\r\n";
unsigned char TxBuffer4[]="\x4E\x45\x58\x8C\x00\r\n"; // Clear Encoder Counts   
unsigned char c1,c2;
unsigned char sum,final_hex[10],hex[5],hex2[5]="0";

ftStatus = FT_GetLibraryVersion(&libraryVersion);
if (ftStatus == FT_OK)
{
    printf("Library version = 0x%x\n", (unsigned int)libraryVersion);
}
else
{
    printf("Error reading library version.\n");
    return 1;
}

if(argc > 1) {
    sscanf(argv[1], "%d", &iport);
}
else {
    iport = 0;
}
printf("Opening port %d\n", iport);

ftStatus = FT_Open(iport, &ftHandle);
if(ftStatus != FT_OK) {
    /* 
        This can fail if the ftdi_sio driver is loaded
        use lsmod to check this and rmmod ftdi_sio to remove
        also rmmod usbserial
     */
    printf("FT_Open(%d) failed\n", iport);
    return 1;
}

printf("FT_Open succeeded.  Handle is %p\n", ftHandle);

ftStatus = FT_SetBaudRate(ftHandle, 57600); // Set baud rate to 115200
if (ftStatus == FT_OK) {
    printf("\nFT_SetBaudRate OK");
}
else {
    printf("\nFT_SetBaudRate Failed");
}
// Set 8 data bits, 1 stop bit and no parity
ftStatus = FT_SetDataCharacteristics(ftHandle, FT_BITS_8, FT_STOP_BITS_1,
FT_PARITY_NONE);
if (ftStatus == FT_OK) {
printf("\nFT_SetDataCharacteristics OK");
}
else {
printf("\nFT_SetDataCharacteristics Failed");
}



    //Step 0. Clearing Counter
printf("\n Clearing Encoder Counts");
ftStatus = FT_Write(ftHandle, TxBuffer4, sizeof(TxBuffer4), &BytesWritten);
if (ftStatus == FT_OK) {
printf("\nFT_Write OK");
}
else {
printf("\nFT_Write Failed");
}
sleep(1);

    //Step 1. Setting Mode

printf("\n Setting Mode to Position Control");
ftStatus = FT_Write(ftHandle, TxBuffer13, sizeof(TxBuffer13), &BytesWritten);
if (ftStatus == FT_OK) 
{
    printf("\nFT_Write OK--> Setting Done \n\n");
}
else
{
    printf("\nSetting Mode Failed");
}






    //Step 3. Moving 0.5mt Forward

printf("\n\n MOVING fORWARD");
ftStatus = FT_Write(ftHandle, TxBuffer16, sizeof(TxBuffer16), &BytesWritten);
if (ftStatus == FT_OK) 
{
    printf("\n\n Stopped");
}
else 
{
    printf("\n Moving Failed");
}



   double x = 0.0;
   double y = 0.0;
   double th = 0.0;

   double vx = 0.1;
   double vy = -0.1;
   double vth = 0.1;

    ros::Time current_time, last_time;
    current_time = ros::Time::now();
    last_time = ros::Time::now();

   ros::Rate r(1.0);
   while(n.ok()){
   current_time = ros::Time::now();

  //compute odometry in a typical way given the velocities of the robot
  double dt = (current_time - last_time).toSec();
  double delta_x = (vx * cos(th) - vy * sin(th)) * dt;
  double delta_y = (vx * sin(th) + vy * cos(th)) * dt;
  double delta_th = vth * dt;

  x += delta_x;
  y += delta_y;
  th += delta_th;

 //since all odometry is 6DOF we'll need a quaternion created from yaw
 geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(th);

 //first, we'll publish the transform over tf
 geometry_msgs::TransformStamped odom_trans;
 odom_trans.header.stamp = current_time;
 odom_trans.header.frame_id = "odom";
 odom_trans.child_frame_id = "base_link";

 odom_trans.transform.translation.x = x;
 odom_trans.transform.translation.y = y;
 odom_trans.transform.translation.z = 0.0;
 odom_trans.transform.rotation = odom_quat;

//send the transform
 odom_broadcaster.sendTransform(odom_trans);

//next, we'll publish the odometry message over ROS
sensor_msgs::Imu fl;
// fl.header.seq=_simulationFrameID;
           fl.header.stamp=current_time;
           fl.orientation.x=0.0; //TODO orientation
           fl.orientation.y=0.0;
           fl.orientation.z=0.0;
           fl.orientation.w=1.0;
           fl.angular_velocity.x=1.3;
           fl.angular_velocity.y=1.2;
           fl.angular_velocity.z=1.5;
           fl.linear_acceleration.x=1.3;
           fl.linear_acceleration.y=1.6;
           fl.linear_acceleration.z=1.4;
//publish the message
imu_pub.publish(fl);

 last_time = current_time;
 r.sleep();
  }
 }

and in My CMakeLists.txt file, I am including ftdi library cmakeminimumrequired(VERSION 2.8.3) project(robot_pose)

   find_package(catkin REQUIRED COMPONENTS nav_msgs sensor_msgs roscpp tf)

   catkin_package()

   include_directories(include ${catkin_INCLUDE_DIRS})
   link_directories(/usr/local/lib)
   find_library(FTDI ftd2xx /usr/local/lib)
   add_executable(imu src/imu.cpp)
   if(sensor_msgs_EXPORTED_TARGETS)
        add_dependencies(imu ${sensor_msgs_EXPORTED_TARGETS})
   endif()
    target_link_libraries(imu ${catkin_LIBRARIES})
   #target_link_libraries(imu ftd2xx)
   target_link_libraries(imu ${FTDI})
     #target_link_libraries(imu libftd2xx.so)
    #target_link_libraries(imu libftd2xx.a)
   install(TARGETS imu
    ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
     LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})

It is showing error

     imu.cpp:(.text+0x5c3): undefined reference to `FT_GetLibraryVersion'
     imu.cpp:(.text+0x671): undefined reference to `FT_Open'
     imu.cpp:(.text+0x6d4): undefined reference to `FT_SetBaudRate'
     imu.cpp:(.text+0x721): undefined reference to `FT_SetDataCharacteristics'
     imu.cpp:(.text+0x781): undefined reference to `FT_Write'
     imu.cpp:(.text+0x7eb): undefined reference to `FT_Write'
     imu.cpp:(.text+0x849): undefined reference to `FT_Write'

Asked by KDROS on 2015-01-22 04:14:18 UTC

Comments

@benny Re @Wolf @Devon W

Asked by KDROS on 2015-01-22 05:00:25 UTC

Have you tried target_link_libraries(imu ${FTDI} ${catkin_LIBRARIES}) ?

Asked by BennyRe on 2015-01-22 06:26:24 UTC

@BennyRe but same error :-(

Asked by KDROS on 2015-01-22 07:22:51 UTC

You said it's a C library right? Try the extern "C" declaration. http://www.oracle.com/technetwork/articles/servers-storage-dev/mixingcandcpluspluscode-305840.html

Asked by BennyRe on 2015-01-26 03:10:22 UTC

I wrote C++ file and used this library with out extern "C", I think there is problem in Cmakelists.txt file.

Asked by KDROS on 2015-01-28 02:24:53 UTC

I think it would be worth a try.

Asked by BennyRe on 2015-01-28 02:49:44 UTC

Closing as this isn't a ROS question. You need to find the right library and pass it to target_link_libraries. You should build using VERBOSE=1 to see what' being linked to help debug.

Asked by tfoote on 2015-03-12 15:59:36 UTC

Answers