Skip to content

Commit

Permalink
Merge branch 'master' into bugfix/KinematicSimulationTrajectoryExecutor
Browse files Browse the repository at this point in the history
  • Loading branch information
gilwoolee authored Apr 22, 2017
2 parents 81ec3c7 + 5d19317 commit c3b212e
Show file tree
Hide file tree
Showing 9 changed files with 351 additions and 8 deletions.
33 changes: 33 additions & 0 deletions cmake/Findpr_control_msgs.cmake
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
# Find pr_control_msgs
#
# This sets the following variables:
# pr_control_msgs_FOUND
# pr_control_msgs_INCLUDE_DIRS
# pr_control_msgs_VERSION

# Note: This find module is necessary because the config file imports "gtest",
# "tests", and "run_tests" that conflict with the targets defined by Aikido.

find_package(PkgConfig QUIET REQUIRED)

# Check to see if pkgconfig is installed.
set(PKG_CONFIG_USE_CMAKE_PREFIX_PATH TRUE)
pkg_check_modules(PC_pr_control_msgs pr_control_msgs QUIET)

# Include directories
find_path(pr_control_msgs_INCLUDE_DIRS
NAMES pr_control_msgs/TriggerResult.h
HINTS ${PC_pr_control_msgs_LIBRARY_DIRS}
)

# Version
set(pr_control_msgs_VERSION ${PC_pr_control_msgs_VERSION})

# Set (NAME)_FOUND if all the variables and the version are satisfied.
include(FindPackageHandleStandardArgs)
find_package_handle_standard_args(pr_control_msgs
FOUND_VAR pr_control_msgs_FOUND
FAIL_MESSAGE DEFAULT_MSG
REQUIRED_VARS pr_control_msgs_INCLUDE_DIRS
VERSION_VAR pr_control_msgs_VERSION
)
9 changes: 9 additions & 0 deletions include/aikido/control/ros/Conversions.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@

#include <memory>
#include <trajectory_msgs/JointTrajectory.h>
#include <sensor_msgs/JointState.h>
#include <aikido/statespace/dart/MetaSkeletonStateSpace.hpp>
#include <aikido/trajectory/Spline.hpp>

Expand All @@ -28,6 +29,14 @@ std::unique_ptr<aikido::trajectory::Spline> toSplineJointTrajectory(
trajectory_msgs::JointTrajectory toRosJointTrajectory(
const aikido::trajectory::TrajectoryPtr& trajectory, double timestep);

/// Converts Eigen VectorXd and joint names to JointState
/// \param[in] goalPositions The required positions for the fingers
/// \param[in] jointNames The corresponding names of the joints
/// \return The JointState message object
sensor_msgs::JointState positionsToJointState(
const Eigen::VectorXd& goalPositions, const std::vector<std::string>& jointNames);


} // namespace ros
} // namespace control
} // namespace aikido
Expand Down
76 changes: 76 additions & 0 deletions include/aikido/control/ros/RosPositionCommandExecutor.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,76 @@
#ifndef AIKIDO_CONTROL_ROS_ROSPOSITIONCOMMANDEXECUTOR_HPP_
#define AIKIDO_CONTROL_ROS_ROSPOSITIONCOMMANDEXECUTOR_HPP_
#include <chrono>
#include <future>
#include <mutex>
#include <ros/ros.h>
#include <ros/callback_queue.h>
#include <sensor_msgs/JointState.h>
#include <pr_control_msgs/SetPositionAction.h>
#include <actionlib/client/action_client.h>
#include <aikido/control/PositionCommandExecutor.hpp>
#include <Eigen/Dense>

namespace aikido{
namespace control {
namespace ros {

/// This class uses actionlib to command an action of the type
/// pr_control_msgs/SetPosition. It specifies a set of target
/// positions and sends it to the ROS server for execution
class RosPositionCommandExecutor : public aikido::control::PositionCommandExecutor
{
public:
/// Constructor
/// \param[in] node ROS node handle for action client.
/// \param[in] serverName Name of the server to send trajectory to.
/// \param[in] The names of the joints to set position targets for
/// \param[in] connectionTimeout Timeout for server connection.
/// \param[in] connectionPollingPeriod Polling period for server connection.
RosPositionCommandExecutor(
::ros::NodeHandle node,
const std::string& serverName,
std::vector<std::string> jointNames,
std::chrono::milliseconds connectionTimeout = std::chrono::milliseconds{1000},
std::chrono::milliseconds connectionPollingPeriod = std::chrono::milliseconds{20}
);

virtual ~RosPositionCommandExecutor();

/// Sends positions to ROS server for execution.
/// \param[in] goalPositions Vector of target positions for each joint
std::future<void> execute(const Eigen::VectorXd& goalPositions) override;


void step() override;

private:
using RosPositionActionClient
= actionlib::ActionClient<pr_control_msgs::SetPositionAction>;
using GoalHandle = RosPositionActionClient::GoalHandle;

bool waitForServer();

void transitionCallback(GoalHandle handle);

::ros::NodeHandle mNode;
::ros::CallbackQueue mCallbackQueue;
RosPositionActionClient mClient;
RosPositionActionClient::GoalHandle mGoalHandle;

std::chrono::milliseconds mConnectionTimeout;
std::chrono::milliseconds mConnectionPollingPeriod;

bool mInProgress;
std::promise<void> mPromise;
Eigen::VectorXd mGoalPositions;
std::vector<std::string> mJointNames;

std::mutex mMutex;
};

} // namespace ros
} // namespace control
} // namespace aikido

#endif // ifndef AIKIDO_CONTROL_ROS_ROSPOSITIONCOMMANDEXECUTOR_HPP_
42 changes: 42 additions & 0 deletions include/aikido/control/ros/detail/util-impl.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
#include <chrono>
#include <mutex>
#include <ros/ros.h>
#include <ros/callback_queue.h>
#include <actionlib/client/action_client.h>

namespace aikido {
namespace control {
namespace ros {

template <class ActionSpec, class TimeoutDuration, class PeriodDuration>
bool waitForActionServer(
actionlib::ActionClient<ActionSpec>& actionClient,
::ros::CallbackQueue& callbackQueue,
TimeoutDuration timeoutDuration = std::chrono::milliseconds{ 1000 },
PeriodDuration periodDuration = std::chrono::milliseconds{ 10 }
)
{
using Clock = std::chrono::steady_clock;

const auto startTime = Clock::now();
const auto endTime = startTime + timeoutDuration;
auto currentTime = startTime;

while(currentTime < endTime)
{
callbackQueue.callAvailable();

// TODO : Is this thread safe?
if (actionClient.isServerConnected())
return true;

currentTime += periodDuration;
std::this_thread::sleep_until(currentTime);
}

return false;
}

} // namespace ros
} // namespace control
} // namespace aikido
26 changes: 26 additions & 0 deletions include/aikido/control/ros/util.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
#ifndef AIKIDO_CONTROL_ROS_UTIL_HPP_
#define AIKIDO_CONTROL_ROS_UTIL_HPP_
#include <chrono>
#include <ros/ros.h>
#include <ros/callback_queue.h>
#include <actionlib/client/action_client.h>

namespace aikido {
namespace control {
namespace ros {

template <class ActionSpec, class TimeoutDuration, class PeriodDuration>
bool waitForActionServer(
actionlib::ActionClient<ActionSpec>& actionClient,
::ros::CallbackQueue& callbackQueue,
TimeoutDuration timeoutDuration = std::chrono::milliseconds{ 1000 },
PeriodDuration periodDuration = std::chrono::milliseconds{ 10 } );


} // namespace ros
} // namespace control
} // namespace aikido

#include "detail/util-impl.hpp"

#endif // AIKIDO_CONTROL_ROS_UTIL_HPP_
1 change: 1 addition & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
<depend>control_msgs</depend>
<depend>libmicrohttpd</depend>
<depend>interactive_markers</depend>
<depend>pr_control_msgs</depend>
<doc_depend>doxygen</doc_depend>
<!-- Workaround to build DART with optional features enabled. -->
<depend>nlopt</depend>
Expand Down
14 changes: 6 additions & 8 deletions src/control/ros/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,12 +1,6 @@
#==============================================================================
# Dependencies
#
find_package(actionlib QUIET)
aikido_check_package(actionlib "aikido::control::ros" "actionlib")

find_package(control_msgs QUIET)
aikido_check_package(control_msgs "aikido::control::ros" "control_msgs")

find_package(roscpp QUIET)
aikido_check_package(roscpp "aikido::control::ros" "roscpp")

Expand All @@ -23,8 +17,10 @@ aikido_check_package(actionlib "aikido::control::ros" "actionlib")
find_package(control_msgs QUIET MODULE)
aikido_check_package(control_msgs "aikido::control::ros" "control_msgs")

find_package(roscpp QUIET)
aikido_check_package(roscpp "aikido::control::ros" "roscpp")
# Note: Intentionally use "Module" mode because the config file imports "gtest",
# "tests", and "run_tests" that conflict with the targets defined by Aikido.
find_package(pr_control_msgs QUIET MODULE)
aikido_check_package(pr_control_msgs "aikido::control::ros" "pr_control_msgs")

#==============================================================================
# Libraries
Expand All @@ -34,6 +30,7 @@ set(sources
RosTrajectoryExecutionException.cpp
Conversions.cpp
RosJointStateClient.cpp
RosPositionCommandExecutor.cpp
)

add_library("${PROJECT_NAME}_control_ros" SHARED ${sources})
Expand All @@ -46,6 +43,7 @@ target_include_directories("${PROJECT_NAME}_control_ros" SYSTEM
${actionlib_INCLUDE_DIRS}
${control_msgs_INCLUDE_DIRS}
${roscpp_INCLUDE_DIRS}
${pr_control_msgs_INCLUDE_DIRS}
)

target_link_libraries("${PROJECT_NAME}_control_ros"
Expand Down
23 changes: 23 additions & 0 deletions src/control/ros/Conversions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -429,6 +429,29 @@ trajectory_msgs::JointTrajectory toRosJointTrajectory(
return jointTrajectory;
}

//=============================================================================
sensor_msgs::JointState positionsToJointState(
const Eigen::VectorXd& goalPositions, const std::vector<std::string>& jointNames)
{
if ((size_t)goalPositions.size() != jointNames.size())
{
std::stringstream message;
message << "The size of goalPositions ("<<goalPositions.size()<<
") must be the same as jointNames ("<<jointNames.size()<<")!" ;
throw std::invalid_argument(message.str());
}

sensor_msgs::JointState jointState;

jointState.name = std::move(jointNames);
jointState.position.assign(goalPositions.data(), goalPositions.data() + goalPositions.size());

return jointState;

}



} // namespace ros
} // namespace control
} // namespace aikido
Loading

0 comments on commit c3b212e

Please sign in to comment.