#include <moveit_bridge.h>
Definition at line 52 of file moveit_bridge.h.
◆ MoveItBridge()
MoveItBridge::MoveItBridge |
( |
| ) |
|
◆ ~MoveItBridge()
MoveItBridge::~MoveItBridge |
( |
| ) |
|
|
virtual |
◆ calcPlannedPath() [1/2]
bool MoveItBridge::calcPlannedPath |
( |
const std::string |
planning_group, |
|
|
open_manipulator_msgs::JointPosition |
msg |
|
) |
| |
◆ calcPlannedPath() [2/2]
bool MoveItBridge::calcPlannedPath |
( |
const std::string |
planning_group, |
|
|
open_manipulator_msgs::KinematicsPose |
msg |
|
) |
| |
◆ controlCallback()
◆ displayPlannedPathMsgCallback()
void MoveItBridge::displayPlannedPathMsgCallback |
( |
const moveit_msgs::DisplayTrajectory::ConstPtr & |
msg | ) |
|
◆ getJointPositionMsgCallback()
bool MoveItBridge::getJointPositionMsgCallback |
( |
open_manipulator_msgs::GetJointPosition::Request & |
req, |
|
|
open_manipulator_msgs::GetJointPosition::Response & |
res |
|
) |
| |
◆ getKinematicsPoseMsgCallback()
bool MoveItBridge::getKinematicsPoseMsgCallback |
( |
open_manipulator_msgs::GetKinematicsPose::Request & |
req, |
|
|
open_manipulator_msgs::GetKinematicsPose::Response & |
res |
|
) |
| |
◆ initPublisher()
void MoveItBridge::initPublisher |
( |
| ) |
|
◆ initServer()
void MoveItBridge::initServer |
( |
| ) |
|
◆ initSubscriber()
void MoveItBridge::initSubscriber |
( |
| ) |
|
◆ setJointPositionMsgCallback()
bool MoveItBridge::setJointPositionMsgCallback |
( |
open_manipulator_msgs::SetJointPosition::Request & |
req, |
|
|
open_manipulator_msgs::SetJointPosition::Response & |
res |
|
) |
| |
◆ setKinematicsPoseMsgCallback()
bool MoveItBridge::setKinematicsPoseMsgCallback |
( |
open_manipulator_msgs::SetKinematicsPose::Request & |
req, |
|
|
open_manipulator_msgs::SetKinematicsPose::Response & |
res |
|
) |
| |
◆ display_planned_path_sub_
◆ get_joint_position_server_
◆ get_kinematics_pose_server_
◆ joint_trajectory_point_pub_
◆ move_group_
◆ nh_
◆ planning_group_
std::string MoveItBridge::planning_group_ |
|
private |
◆ priv_nh_
◆ set_joint_position_server_
◆ set_kinematics_pose_server_
◆ use_gazebo_
bool MoveItBridge::use_gazebo_ |
|
private |
The documentation for this class was generated from the following files: