#include <boxpick_client.h>

Public Member Functions | |
| BoxpickClient (const std::string &host, const ros::NodeHandle &nh) | |
| ~BoxpickClient ()=default | |
Public Member Functions inherited from ros_pick_client::PickClient | |
| PickClient (const std::string &host, const std::string &node_name, const ros::NodeHandle &nh) | |
| virtual | ~PickClient () |
Private Member Functions | |
| bool | computeGraspsSrv (rc_pick_client::ComputeBoxGraspsRequest &request, rc_pick_client::ComputeBoxGraspsResponse &response) |
| bool | detectItemsSrv (rc_pick_client::DetectItemsRequest &request, rc_pick_client::DetectItemsResponse &response) |
| void | dynamicReconfigureCallback (rc_pick_client::pickModuleConfig &config, uint32_t) |
Private Attributes | |
| ros::ServiceServer | srv_compute_grasps_ |
| ros::ServiceServer | srv_detect_items_ |
Additional Inherited Members | |
Protected Member Functions inherited from ros_pick_client::PickClient | |
| template<typename Request , typename Response > | |
| bool | callService (const std::string &name, const Request &req, Response &res) |
| json | createSharedParameters (rc_pick_client::pickModuleConfig &config) |
| void | initConfiguration () |
| void | paramsToCfg (const json ¶ms, rc_pick_client::pickModuleConfig &cfg) |
| void | startPick () |
| void | stopPick () |
Protected Attributes inherited from ros_pick_client::PickClient | |
| ros::NodeHandle | nh_ |
| rc_rest_api::RestHelper | rest_helper_ |
| std::unique_ptr< dynamic_reconfigure::Server< rc_pick_client::pickModuleConfig > > | server_ |
| pick_visualization::Visualization | visualizer_ |
Definition at line 42 of file boxpick_client.h.
| ros_pick_client::BoxpickClient::BoxpickClient | ( | const std::string & | host, |
| const ros::NodeHandle & | nh | ||
| ) |
Definition at line 37 of file boxpick_client.cpp.
|
default |
|
private |
Definition at line 44 of file boxpick_client.cpp.
|
private |
Definition at line 53 of file boxpick_client.cpp.
|
privatevirtual |
Implements ros_pick_client::PickClient.
Definition at line 62 of file boxpick_client.cpp.
|
private |
Definition at line 58 of file boxpick_client.h.
|
private |
Definition at line 57 of file boxpick_client.h.