diff --git a/include/aikido/control/ros/RosTrajectoryExecutor.hpp b/include/aikido/control/ros/RosTrajectoryExecutor.hpp index 374905c76b..d3e6dd2f99 100644 --- a/include/aikido/control/ros/RosTrajectoryExecutor.hpp +++ b/include/aikido/control/ros/RosTrajectoryExecutor.hpp @@ -20,7 +20,6 @@ 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. @@ -28,7 +27,6 @@ class RosTrajectoryExecutor : public aikido::control::TrajectoryExecutor /// \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, @@ -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; diff --git a/src/control/ros/RosTrajectoryExecutor.cpp b/src/control/ros/RosTrajectoryExecutor.cpp index 912ebc1f96..15044c48cf 100644 --- a/src/control/ros/RosTrajectoryExecutor.cpp +++ b/src/control/ros/RosTrajectoryExecutor.cpp @@ -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} @@ -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."); @@ -109,12 +104,6 @@ std::future 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;