Skip to content

Commit

Permalink
point-streaming: address some of the comments made in PR ros-industri…
Browse files Browse the repository at this point in the history
…al#88

* Addressed comments from @shaun-edwards:
  - Comment 1: Made JointTrajectoryInterface::jointCommandCB() pure
    virtual so that JointTrajectoryInterface::jointCommandCB()
    implementation can be deleted.
  - Comment 2: Message was changed to ROS_DEBUG
* Some other minor changes (e.g., commenting)
  • Loading branch information
tdl-ua committed May 16, 2018
1 parent 5b3326e commit 7b316da
Show file tree
Hide file tree
Showing 4 changed files with 14 additions and 12 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -300,7 +300,13 @@ class JointTrajectoryInterface
*/
virtual void jointTrajectoryCB(const trajectory_msgs::JointTrajectoryConstPtr &msg);

virtual void jointCommandCB(const trajectory_msgs::JointTrajectoryConstPtr &msg);
/**
* \brief Callback function registered to joint_command topic subscriber.
* Specific method is implemented in JointTrajectoryStreamer class.
*
* \param msg JointTrajectory message
*/
virtual void jointCommandCB(const trajectory_msgs::JointTrajectoryConstPtr &msg) = 0;

/**
* \brief Callback function registered to ROS stopMotion service
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -271,12 +271,6 @@ void JointTrajectoryInterface::jointTrajectoryCB(
send_to_robot(robot_msgs);
}

void JointTrajectoryInterface::jointCommandCB(
const trajectory_msgs::JointTrajectoryConstPtr &msg)
{
//ROS_INFO("Yessir?");
}

bool JointTrajectoryInterface::trajectory_to_msgs(
const motoman_msgs::DynamicJointTrajectoryConstPtr& traj,
std::vector<SimpleMessage>* msgs)
Expand Down Expand Up @@ -741,4 +735,3 @@ void JointTrajectoryInterface::jointStateCB(

} // namespace joint_trajectory_interface
} // namespace industrial_robot_client

Original file line number Diff line number Diff line change
Expand Up @@ -345,7 +345,7 @@ void JointTrajectoryStreamer::streamingThread()
break;

case TransferStates::POINT_STREAMING:
ROS_INFO("I'm streaming, sir.");

// if no points in queue, streaming complete, set to idle.
if (this->streaming_queue_.empty())
{
Expand Down Expand Up @@ -376,7 +376,11 @@ void JointTrajectoryStreamer::streamingThread()
ROS_WARN("Failed sent joint point, will try again");

break;
// consider checking for controller point starvation here. use a timer to check if the state is popping in and out of POINT_STREAMING mode, indicating something is trying to send streaming points, but is doing so too slowly. It may, in fact, not matter other than motion won't be smooth.
// TODO Consider checking for controller point starvation here. use a
// timer to check if the state is popping in and out of
// POINT_STREAMING mode, indicating something is trying to send
// streaming points, but is doing so too slowly. It may, in fact, not
// matter other than motion won't be smooth.

default:
ROS_ERROR("Joint trajectory streamer: unknown state, %d", this->state_);
Expand All @@ -400,4 +404,3 @@ void JointTrajectoryStreamer::trajectoryStop()

} // namespace joint_trajectory_streamer
} // namespace industrial_robot_client

2 changes: 1 addition & 1 deletion motoman_driver/src/joint_trajectory_streamer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -469,7 +469,7 @@ void MotomanJointTrajectoryStreamer::streamingThread()
{
time_since_last = ros::Time::now().toSec() - time_of_last;
ros::Duration(0.005).sleep();
//ROS_INFO("Time since last point: %f", time_since_last);
ROS_DEBUG("Time since last point: %f", time_since_last);
break;
}
else
Expand Down

0 comments on commit 7b316da

Please sign in to comment.