11 #ifndef HTTP_COMMAND_INTERFACE_H 12 #define HTTP_COMMAND_INTERFACE_H 15 #include <boost/property_tree/ptree.hpp> 37 bool setParameter(
const std::string name,
const std::string value);
42 boost::optional<std::string>
getParameter(
const std::string name);
47 std::map< std::string, std::string >
getParameters(
const std::vector< std::string >& names );
67 boost::optional<HandleInfo>
requestHandleUDP(
int port, std::string hostname = std::string(
""),
int start_angle=-1800000);
99 int httpGet(
const std::string request_path, std::string&
header, std::string& content);
104 bool sendHttpCommand(
const std::string cmd,
const std::map< std::string, std::string > param_values );
110 bool sendHttpCommand(
const std::string cmd,
const std::string
param =
"",
const std::string value =
"" );
123 boost::property_tree::ptree
pt_;
131 #endif // HTTP_COMMAND_INTERFACE_H bool param(const std::string ¶m_name, T ¶m_val, const T &default_val)
bool setParameter(const std::string name, const std::string value)
int httpGet(const std::string request_path, std::string &header, std::string &content)
bool startScanOutput(const std::string &handle)
Initiate output of scan data.
bool sendHttpCommand(const std::string cmd, const std::map< std::string, std::string > param_values)
bool resetParameters(const std::vector< std::string > &names)
boost::optional< HandleInfo > requestHandleTCP(int start_angle=-1800000)
HttpCommandInterface(const std::string &http_host, int http_port=80)
const std::string & getHttpHost() const
Get the HTTP hostname/IP of the scanner.
boost::optional< std::string > getParameter(const std::string name)
std_msgs::Header * header(M &m)
bool releaseHandle(const std::string &handle)
Release handle.
int http_status_code_
HTTP-Status code of last request.
std::map< std::string, std::string > getParameters(const std::vector< std::string > &names)
bool rebootDevice()
Reboot laserscanner.
std::string discoverLocalIP()
boost::optional< HandleInfo > requestHandleUDP(int port, std::string hostname=std::string(""), int start_angle=-1800000)
Allows accessing the HTTP/JSON interface of the Pepperl+Fuchs Laserscanner R2000. ...
std::string http_host_
Scanner IP.
boost::optional< ProtocolInfo > getProtocolInfo()
int http_port_
Port of HTTP-Interface.
bool stopScanOutput(const std::string &handle)
Terminate output of scan data.
boost::property_tree::ptree pt_
Returned JSON as property_tree.
std::vector< std::string > getParameterList()
bool feedWatchdog(const std::string &handle)
Feed the watchdog to keep the handle alive.