Skip to content

Commit 86c98f3

Browse files
tdl-uaGerald Meurant
authored andcommitted
point-streaming: address some of the comments made in PR ros-industrial#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)
1 parent 94b695e commit 86c98f3

File tree

4 files changed

+14
-12
lines changed

4 files changed

+14
-12
lines changed

motoman_driver/include/motoman_driver/industrial_robot_client/joint_trajectory_interface.h

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -301,7 +301,13 @@ class JointTrajectoryInterface
301301
*/
302302
virtual void jointTrajectoryCB(const trajectory_msgs::JointTrajectoryConstPtr &msg);
303303

304-
virtual void jointCommandCB(const trajectory_msgs::JointTrajectoryConstPtr &msg);
304+
/**
305+
* \brief Callback function registered to joint_command topic subscriber.
306+
* Specific method is implemented in JointTrajectoryStreamer class.
307+
*
308+
* \param msg JointTrajectory message
309+
*/
310+
virtual void jointCommandCB(const trajectory_msgs::JointTrajectoryConstPtr &msg) = 0;
305311

306312
/**
307313
* \brief Callback function registered to ROS stopMotion service

motoman_driver/src/industrial_robot_client/joint_trajectory_interface.cpp

Lines changed: 0 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -271,12 +271,6 @@ void JointTrajectoryInterface::jointTrajectoryCB(
271271
send_to_robot(robot_msgs);
272272
}
273273

274-
void JointTrajectoryInterface::jointCommandCB(
275-
const trajectory_msgs::JointTrajectoryConstPtr &msg)
276-
{
277-
//ROS_INFO("Yessir?");
278-
}
279-
280274
bool JointTrajectoryInterface::trajectory_to_msgs(
281275
const motoman_msgs::DynamicJointTrajectoryConstPtr& traj,
282276
std::vector<SimpleMessage>* msgs)
@@ -745,4 +739,3 @@ void JointTrajectoryInterface::jointStateCB(
745739

746740
} // namespace joint_trajectory_interface
747741
} // namespace industrial_robot_client
748-

motoman_driver/src/industrial_robot_client/joint_trajectory_streamer.cpp

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -347,7 +347,7 @@ void JointTrajectoryStreamer::streamingThread()
347347
break;
348348

349349
case TransferStates::POINT_STREAMING:
350-
ROS_INFO("I'm streaming, sir.");
350+
351351
// if no points in queue, streaming complete, set to idle.
352352
if (this->streaming_queue_.empty())
353353
{
@@ -378,7 +378,11 @@ void JointTrajectoryStreamer::streamingThread()
378378
ROS_WARN("Failed sent joint point, will try again");
379379

380380
break;
381-
// 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.
381+
// TODO Consider checking for controller point starvation here. use a
382+
// timer to check if the state is popping in and out of
383+
// POINT_STREAMING mode, indicating something is trying to send
384+
// streaming points, but is doing so too slowly. It may, in fact, not
385+
// matter other than motion won't be smooth.
382386

383387
default:
384388
ROS_ERROR("Joint trajectory streamer: unknown state, %d", this->state_);
@@ -402,4 +406,3 @@ void JointTrajectoryStreamer::trajectoryStop()
402406

403407
} // namespace joint_trajectory_streamer
404408
} // namespace industrial_robot_client
405-

motoman_driver/src/joint_trajectory_streamer.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -524,7 +524,7 @@ void MotomanJointTrajectoryStreamer::streamingThread()
524524
{
525525
time_since_last = ros::Time::now().toSec() - time_of_last;
526526
ros::Duration(0.005).sleep();
527-
//ROS_INFO("Time since last point: %f", time_since_last);
527+
ROS_DEBUG("Time since last point: %f", time_since_last);
528528
break;
529529
}
530530
else

0 commit comments

Comments
 (0)