Skip to content

Not possible to retrieve Vtcp AO signal #157

@kappa95

Description

@kappa95

Dear community,

I am trying to use the library for reading the Analog Output signals particularly the one of the speed that at the moment I am writing on a CSV file from the robot controller using rapid. Now I would like to get the signals from TCP speed. I have set on the virtual controller the System Output signals to get the TCP speed. The issue is that if i am trying to printout the TCP speed I get always 0.
Read and writing DO works perfectly and also EGM with abb_libegm but I am interested in TCP speed.
I post my code:

#include <fstream>
#include <iostream>
#include <sstream>
#include <string>
#include <vector>
#include <thread>
#include <chrono>
#include "abb_libegm/egm_trajectory_interface.h"
#include "abb_librws/rws_interface.h"
#include "spdlog/spdlog.h"
#include "spdlog/sinks/basic_file_sink.h"


int main()
{
  std::cout << "MIRACOLO COMPILA!!\n";
  // Boost components for asynch UDP sockets
  boost::asio::io_service io_service;
  boost::thread_group thread_group;
  using namespace std::this_thread;     // sleep_for, sleep_until
  using std::chrono::system_clock;

  // Creo un logger
  auto logger = spdlog::basic_logger_mt("logger_basic", "fede_logs/basic-log.log");
  // Nome del segnale analogico
  std::string ao_sig_vtcp = "tcpspeed";
  std::string ao_sig_vtcp_ref = "vtcprefAO";
  // Ip del robot
  std::string rws_ip_address = "192.168.125.42";
  // Create a RWS interface:
  // * Sets up a RWS client (that can connect to the robot controller's RWS server).
  // * Provides APIs to the user (for accessing the RWS server's services).
  //
  // Note: It is important to set the correct IP-address here, to the RWS server.
  abb::rws::RWSInterface rws_interface(rws_ip_address);
  // EGM INTERFACE: the EGMTraj inherits from EGMBaseInterface
  abb::egm::EGMTrajectoryInterface egm_interface(io_service, 6511);

  // Check if egm_interface has been init.
  if(!egm_interface.isInitialized())
  {
    
    spdlog::error("egm_interface failed to init\n");
    return 0;
  }

  // Spin up a thread to run the io_service
  thread_group.create_thread(boost::bind(&boost::asio::io_service::run, &io_service));
  std::string path = "/home/kappa95/abb_ws/src/abb_libegm_samples/src/";
  std::string filename;
  std::cout << "put filename: \n";
  std::cin >> filename;
  // ifstream class is used for reading files
  // std::ifstream inputfile{"/home/kappa95/abb_ws/src/abb_libegm_samples/src/sample.txt"};
  std::ifstream inputfile{path + filename};
  std::vector <std::vector<float>> poses;
  if (!inputfile)
  {
    spdlog::error("Cant open the file\n");
    return 1;
  }

  // Read until there is stuff to read
  while (inputfile)
  {
    // Read each line and print it
    std::string strInput;
    std::vector<float> v;
    std::getline(inputfile, strInput);
    if (strInput == "")
      continue;

    std::stringstream ss(strInput);
    float val;
    while (ss >> val)
    {
      v.push_back(val);
      //std::cout << val << std::endl;
    }
    //std::cout << "stringa: " << strInput << std::endl;
    // push back into poses
    poses.push_back(v);
  }

  spdlog::info("Now i print the matrix");
  //std::cout << "Now i print the matrix\n";
  for (size_t i = 0; i < poses.size(); i++)
  {
    for (size_t j = 0; j < poses[i].size(); j++)
    {
      std::cout << poses[i][j] << " ";
    }
    std::cout << std::endl;
  }

  std::cout << "Poses number: " << poses.size();
  // Now I have to make the part for controlling the robot

  bool wait = true;
  spdlog::info("Filling the trajectory");
  //ROS_INFO("Filling the trajectory");
  abb::egm::wrapper::trajectory::TrajectoryGoal trajectory;
  abb::egm::wrapper::trajectory::PointGoal *p_point;

  // Filling the trajectory
  for (size_t i = 0; i < poses.size(); i++)
  {
    spdlog::info("FILLING POINT: {}", i);
    // Adding the points to the trajectory
    p_point = trajectory.add_points(); // add the pointer of the points to the traj
    p_point->set_reach(true);  // Specify If it is important to reach the position
    p_point->set_duration(0.42);  // seconds of the time that i want to reach the position: depends on the speed
    
    // Set position!
    p_point->mutable_robot()->mutable_cartesian()->mutable_pose()->mutable_position()->set_x(poses[i][0]);
    p_point->mutable_robot()->mutable_cartesian()->mutable_pose()->mutable_position()->set_y(poses[i][1]);
    p_point->mutable_robot()->mutable_cartesian()->mutable_pose()->mutable_position()->set_z(poses[i][2]);
    // Set the orientation euler XYZ!
    p_point->mutable_robot()->mutable_cartesian()->mutable_pose()->mutable_euler()->set_x(poses[i][3]);
    p_point->mutable_robot()->mutable_cartesian()->mutable_pose()->mutable_euler()->set_y(poses[i][4]);
    p_point->mutable_robot()->mutable_cartesian()->mutable_pose()->mutable_euler()->set_z(poses[i][5]);
    spdlog::info("X-Y-Z: {} - {} - {} RXYZ: {}° - {}° - {}°",poses[i][0], poses[i][1], poses[i][2], poses[i][3], poses[i][4], poses[i][5]);
  }
  logger->info("Testing!!!");
  // Wait until the EGM is not enabled:
  spdlog::info("1: Wait for an EGM communication session to start...");
  while(wait)
  {
    if(egm_interface.isConnected())
    {
      if(egm_interface.getStatus().rapid_execution_state() == abb::egm::wrapper::Status_RAPIDExecutionState_RAPID_UNDEFINED)
      {
        spdlog::warn("RAPID execution state is UNDEFINED (might happen first time after controller start/restart). Try to restart the RAPID program.");
      }
      else
      {
        wait = egm_interface.getStatus().rapid_execution_state() != abb::egm::wrapper::Status_RAPIDExecutionState_RAPID_RUNNING;
      }
    }

    sleep_for(std::chrono::milliseconds(500));
  }

  spdlog::info("2: Add a pose trajectory to the execution queue");
  egm_interface.addTrajectory(trajectory);

  spdlog::info("3: Wait for the trajectory execution to finish...");
  abb::egm::wrapper::trajectory::ExecutionProgress execution_progress;
  wait = true;
  while(wait)
  {
    sleep_for(std::chrono::milliseconds(250));

    if (egm_interface.retrieveExecutionProgress(&execution_progress))
    {
      //spdlog::info("VTCP signal: {} - VTCP ref: {}", rws_interface.getIOSignal(ao_sig_vtcp), rws_interface.getIOSignal(ao_sig_vtcp_ref));
      spdlog::info("VTCP signal: {}", rws_interface.getIOSignal(ao_sig_vtcp));
      wait = execution_progress.goal_active();
    }
  }

  // Perform a clean shutdown.
  io_service.stop();
  thread_group.join_all();

  return 0;
}

Metadata

Metadata

Assignees

No one assigned

    Labels

    No labels
    No labels

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions