bool MotomanJointTrajectoryStreamer::VectorToJointData(const std::vector<double> &vec,
    JointData &joints)
{
  if (vec.size() > joints.getMaxNumJoints())
    ROS_ERROR_RETURN(false, "Failed to copy to JointData.  Len (%d) out of range (0 to %d)",
                     vec.size(), joints.getMaxNumJoints());

  joints.init();
  for (int i = 0; i < vec.size(); ++i)
  {
    joints.setJoint(i, vec[i]);
  }
  return true;
}
Beispiel #2
0
TEST(DISABLED_TrajectoryJob, init)
{

  using namespace std;

  TrajectoryJob job;
  JointTraj traj;
  JointTrajPt pt;
  JointData init;
  string job_name = "JOB_NAME";
  string job_ext = ".JBI";

  const int TRAJ_SIZE = 50;
  const int BIG_JOB_BUFFER_SIZE = 500000;
  char bigJobBuffer[BIG_JOB_BUFFER_SIZE];
  const int SMALL_JOB_BUFFER_SIZE = 10;
  char smallJobBuffer[SMALL_JOB_BUFFER_SIZE];

  for (int i = 1; i <= TRAJ_SIZE; i++)
  {
    //ROS_DEBUG("Initializing joint: %d", i);
    for (int j = 0; j < init.getMaxNumJoints(); j++)
    {
      //ROS_DEBUG("Initializing point: %d.%d", i, j);
      ASSERT_TRUE(init.setJoint(j, (i*(j+1))));
    }
    pt.init(i, init, 11.1111, 0.01);
    ASSERT_TRUE(traj.addPoint(pt));
  }

  EXPECT_FALSE(job.init("this name is way too long to be the name of a file and this should fail"));
  ASSERT_TRUE(job.init((char*)job_name.c_str()));

  EXPECT_FALSE(job.toJobString(traj, &smallJobBuffer[0], SMALL_JOB_BUFFER_SIZE));
  // Test is disabled because the line below fails due to missing conversions functions.  This
  // ability has been moved to the controller and now is dynamically updated at runtime.  There
  // may not be a solution to this issue.
  EXPECT_TRUE(job.toJobString(traj, &bigJobBuffer[0], BIG_JOB_BUFFER_SIZE));
  ofstream file;
  job_name.append(job_ext);
  file.open(job_name.c_str());
  ASSERT_TRUE(file.is_open());
  file << bigJobBuffer;
  file.close();


}
void JointTrajectoryDownloader::jointTrajectoryCB(
		const trajectory_msgs::JointTrajectoryConstPtr &msg)
{
	ROS_INFO("Receiving joint trajectory message");

  /*
	if (!checkTrajectory(msg))
	{
		ROS_ERROR("Joint trajectory check failed, trajectory not downloaded");
		return;
	}

	std::vector<double> joint_velocity_limits;
	if (!getVelocityLimits("robot_description", msg->joint_names, joint_velocity_limits))
	{
		ROS_ERROR("Failed to get joint velocity limits");
		return;
	}
  */
	for (int i = 0; i < msg->points.size(); i++)
	{
		ROS_INFO("Sending joints trajectory point[%d]", i);

		JointTrajPt jPt;
		JointTrajPtMessage jMsg;
		SimpleMessage topic;
		trajectory_msgs::JointTrajectoryPoint pt;

		pt = msg->points[i];

		// The first and last sequence values must be given a special sequence
		// value
		if (0 == i)
		{
			ROS_DEBUG("First trajectory point, setting special sequence value");
			jPt.setSequence(SpecialSeqValues::START_TRAJECTORY_DOWNLOAD);
		}
		else if (msg->points.size() - 1 == i)
		{
			ROS_DEBUG("Last trajectory point, setting special sequence value");
			jMsg.point_.setSequence(SpecialSeqValues::END_TRAJECTORY);
		}
		else
		{
			jMsg.point_.setSequence(i);
		}

		// Copy position data to local variable
		JointData data;
		for (int j = 0; j < msg->joint_names.size(); j++)
		{
			pt = msg->points[j];
			data.setJoint(j, pt.positions[j]);
		}

		// Initialize joint trajectory message
		jPt.setJointPosition(data);

		jMsg.init(jPt);
		jMsg.toTopic(topic);

		ROS_DEBUG("Sending joint trajectory point");
		if (this->robot_->sendMsg(topic))
		{
			ROS_INFO("Point[%d] sent to controller", i);
		}
		else
		{
			ROS_WARN("Failed sent joint point, skipping point");
		}
	}
}
void JointTrajectoryDownloader::jointTrajectoryCB(
		const trajectory_msgs::JointTrajectoryConstPtr &msg)
{
	ROS_INFO("Receiving joint trajectory message");

	// TBD: re-enable in a more generic fashion?
	//if (!checkTrajectory(msg))
	//{
	//	ROS_ERROR("Joint trajectory check failed, trajectory not downloaded");
	//	return;
	//}
  
	std::vector<double> joint_velocity_limits;
	std::vector<trajectory_msgs::JointTrajectoryPoint> points(msg->points);
  
	// TBD: re-enable velocity scaling
	//if (!getVelocityLimits("robot_description", msg, joint_velocity_limits))
	//{
	//	ROS_ERROR("Failed to get joint velocity limits");
	//	return;
	//}

	// Trajectory download requires at least two points (START/END)
        if (points.size() < 2)
          points.push_back(trajectory_msgs::JointTrajectoryPoint(points[0]));

  if (!this->robot_->isConnected())
  {
    ROS_WARN("Attempting robot reconnection");
    this->robot_->makeConnect();
  }
  
  ROS_INFO("Sending trajectory points, size: %d", points.size());

	for (int i = 0; i < points.size(); i++)
	{
		ROS_INFO("Sending joints trajectory point[%d]", i);

		JointTrajPt jPt;
		JointTrajPtMessage jMsg;
		SimpleMessage topic;

		// Performing a manual copy of the joint velocities in order to send them
    // to the utility function.  Passing the pt data members doesn't seem to
    // work.
    std::vector<double> joint_velocities(0.0);
    double velocity =0 ;
    joint_velocities.resize(msg->joint_names.size(), 0.0);
    for (int j = 0; j < joint_velocities.size(); j++)
    {
      joint_velocities[j] = points[i].velocities[j];
    }

    ROS_DEBUG("Joint velocities copied");
    // TBD: restore joint-velocity scaling
    //velocity = toMotomanVelocity(joint_velocity_limits, joint_velocities);
    velocity = 0.20;  // TBD: hardcode for now

    jPt.setVelocity(velocity);

		// The first and last sequence values must be given a special sequence
		// value
		if (0 == i)
		{
			ROS_DEBUG("First trajectory point, setting special sequence value");
			jPt.setSequence(SpecialSeqValues::START_TRAJECTORY_DOWNLOAD);
		}
		else if (points.size() - 1 == i)
		{
			ROS_DEBUG("Last trajectory point, setting special sequence value");
			jPt.setSequence(SpecialSeqValues::END_TRAJECTORY);
		}
		else
		{
			jPt.setSequence(i);
		}

		// Copy position data to local variable
		JointData data;
		for (int j = 0; j < msg->joint_names.size(); j++)
		{
			data.setJoint(j, points[i].positions[j]);
		}

		// Initialize joint trajectory message
		jPt.setJointPosition(data);
		jMsg.init(jPt);
		jMsg.toTopic(topic);

		ROS_DEBUG("Sending joint trajectory point");
		if (this->robot_->sendMsg(topic))
		{
			ROS_INFO("Point[%d] sent to controller", i);
		}
		else
		{
			ROS_WARN("Failed sent joint point, skipping point");
		}
	}
}