Models the outcome of drake::FindResource.
After a call to FindResource, typical calling code would use get_absolute_path_or_throw(). Alternatively, get_absolute_path() will return an optional<string>, which can be manually checked to contain a value before using the path. If the resource was not found, get_error_message() will contain an error message.
For a given FindResourceResult instance, exactly one of get_absolute_path() or get_error_message() will contain a value. (Similarly, exactly one of them will not contain a value.)
#include <drake/common/find_resource.h>
Public Member Functions | |
| std::optional< std::string > | get_absolute_path () const | 
| Returns the absolute path to the resource, iff the resource was found.  More... | |
| std::string | get_absolute_path_or_throw () const | 
| Either returns the get_absolute_path() iff the resource was found, or else throws std::exception.  More... | |
| std::optional< std::string > | get_error_message () const | 
| Returns the error message, iff the resource was not found.  More... | |
| std::string | get_resource_path () const | 
| Returns the resource_path asked of FindResource.  More... | |
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable  | |
| FindResourceResult (const FindResourceResult &)=default | |
| FindResourceResult & | operator= (const FindResourceResult &)=default | 
| FindResourceResult (FindResourceResult &&)=default | |
| FindResourceResult & | operator= (FindResourceResult &&)=default | 
Static Public Member Functions | |
| static FindResourceResult | make_success (std::string resource_path, std::string absolute_path) | 
| Returns a success result (the requested resource was found).  More... | |
| static FindResourceResult | make_error (std::string resource_path, std::string error_message) | 
| Returns an error result (the requested resource was NOT found).  More... | |
| static FindResourceResult | make_empty () | 
| Returns an empty error result (no requested resource).  More... | |
      
  | 
  default | 
      
  | 
  default | 
| std::optional<std::string> get_absolute_path | ( | ) | const | 
Returns the absolute path to the resource, iff the resource was found.
| std::string get_absolute_path_or_throw | ( | ) | const | 
Either returns the get_absolute_path() iff the resource was found, or else throws std::exception.
| std::optional<std::string> get_error_message | ( | ) | const | 
Returns the error message, iff the resource was not found.
The string will never be empty; only the optional can be empty.
| std::string get_resource_path | ( | ) | const | 
Returns the resource_path asked of FindResource.
(This may be empty only in the make_empty() case.)
      
  | 
  static | 
Returns an empty error result (no requested resource).
      
  | 
  static | 
Returns an error result (the requested resource was NOT found).
| resource_path | the value passed to FindResource | 
      
  | 
  static | 
Returns a success result (the requested resource was found).
| resource_path | the value passed to FindResource | 
| absolute_path | an absolute base path that precedes resource_path | 
      
  | 
  default | 
      
  | 
  default |