Skip to content

Commit

Permalink
Merge branch 'master' into style/statespace
Browse files Browse the repository at this point in the history
  • Loading branch information
jslee02 authored Apr 23, 2017
2 parents 3733a66 + dffdf28 commit bcb5cf8
Show file tree
Hide file tree
Showing 2 changed files with 1 addition and 15 deletions.
3 changes: 0 additions & 3 deletions include/aikido/control/ros/RosTrajectoryExecutor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,15 +20,13 @@ class RosTrajectoryExecutor : public aikido::control::TrajectoryExecutor
{
public:
/// Constructor.
/// \param[in] space Space in which trajectries operate.
/// \param[in] node ROS node handle for action client.
/// \param[in] serverName Name of the server to send traejctory to.
/// \param[in] timestep Step size for interpolating trajectories.
/// \param[in] goalTimeTolerance
/// \param[in] connectionTimeout Timeout for server connection.
/// \param[in] connectionPollingPeriod Polling period for server connection.
RosTrajectoryExecutor(
statespace::dart::MetaSkeletonStateSpacePtr space,
::ros::NodeHandle node,
const std::string& serverName,
double timestep,
Expand Down Expand Up @@ -66,7 +64,6 @@ class RosTrajectoryExecutor : public aikido::control::TrajectoryExecutor

void transitionCallback(GoalHandle handle);

statespace::dart::MetaSkeletonStateSpacePtr mSpace;
::ros::NodeHandle mNode;
::ros::CallbackQueue mCallbackQueue;
TrajectoryActionClient mClient;
Expand Down
13 changes: 1 addition & 12 deletions src/control/ros/RosTrajectoryExecutor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,15 +49,13 @@ std::string getFollowJointTrajectoryErrorMessage(int32_t errorCode)

//=============================================================================
RosTrajectoryExecutor::RosTrajectoryExecutor(
statespace::dart::MetaSkeletonStateSpacePtr space,
::ros::NodeHandle node,
const std::string& serverName,
double timestep,
double goalTimeTolerance,
const std::chrono::milliseconds& connectionTimeout,
const std::chrono::milliseconds& connectionPollingPeriod)
: mSpace{std::move(space)}
, mNode{std::move(node)}
: mNode{std::move(node)}
, mCallbackQueue{}
, mClient{mNode, serverName, &mCallbackQueue}
, mTimestep{timestep}
Expand All @@ -66,9 +64,6 @@ RosTrajectoryExecutor::RosTrajectoryExecutor(
, mConnectionPollingPeriod{connectionPollingPeriod}
, mInProgress{false}
{
if (!mSpace)
throw std::invalid_argument("Space is null.");

if (mTimestep <= 0)
throw std::invalid_argument("Timestep must be positive.");

Expand Down Expand Up @@ -109,12 +104,6 @@ std::future<void> RosTrajectoryExecutor::execute(
"Trajectory is not in a MetaSkeletonStateSpace.");
}

if (space != mSpace)
{
throw std::invalid_argument(
"Trajectory is not in the same StateSpace as this RosTrajectoryExecutor.");
}

// Setup the goal properties.
// TODO: Also set goal_tolerance, path_tolerance.
control_msgs::FollowJointTrajectoryGoal goal;
Expand Down

0 comments on commit bcb5cf8

Please sign in to comment.