Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fixes to work on real hardware #216

Merged
merged 4 commits into from
Aug 23, 2017
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions include/aikido/control/ros/RosTrajectoryExecutor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,11 +40,11 @@ class RosTrajectoryExecutor : public aikido::control::TrajectoryExecutor
virtual ~RosTrajectoryExecutor();

/// Sends trajectory to ROS server for execution.
/// \param[in] traj Trajecotry to be executed.
/// \param[in] traj Trajectory to be executed.
std::future<void> execute(trajectory::TrajectoryPtr traj) override;

/// Sends trajectory to ROS server for execution.
/// \param[in] traj Trajectrory to be executed.
/// \param[in] traj Trajectory to be executed.
/// \param[in] startTime Start time for the trajectory.
std::future<void> execute(
trajectory::TrajectoryPtr traj, const ::ros::Time& startTime);
Expand Down
2 changes: 1 addition & 1 deletion src/control/ros/RosJointStateClient.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,7 @@ void RosJointStateClient::jointStateCallback(
boost::circular_buffer<JointStateRecord>{mCapacity});
auto& buffer = result.first->second;

if (_jointState.header.stamp < buffer.back().mStamp)
if (!buffer.empty() && _jointState.header.stamp < buffer.back().mStamp)
{
// Ignore out of order JointState message.
ROS_WARN_STREAM(
Expand Down