Classes | Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | List of all members
joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface > Class Template Reference

Controller for executing joint-space trajectories on a group of joints. More...

#include <joint_trajectory_controller.h>

Inheritance diagram for joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >:
Inheritance graph
[legend]

Classes

struct  TimeData
 

Public Member Functions

 JointTrajectoryController ()
 
Non Real-Time Safe Functions
bool init (HardwareInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
 
Real-Time Safe Functions
void starting (const ros::Time &time)
 Holds the current position. More...
 
void stopping (const ros::Time &)
 Cancels the active action goal, if any. More...
 
void update (const ros::Time &time, const ros::Duration &period)
 
- Public Member Functions inherited from controller_interface::Controller< HardwareInterface >
 Controller ()
 
virtual bool init (HardwareInterface *, ros::NodeHandle &)
 
virtual ~Controller ()
 
- Public Member Functions inherited from controller_interface::ControllerBase
 ControllerBase ()
 
bool isRunning ()
 
bool isRunning ()
 
bool startRequest (const ros::Time &time)
 
bool startRequest (const ros::Time &time)
 
bool stopRequest (const ros::Time &time)
 
bool stopRequest (const ros::Time &time)
 
void updateRequest (const ros::Time &time, const ros::Duration &period)
 
void updateRequest (const ros::Time &time, const ros::Duration &period)
 
virtual ~ControllerBase ()
 

Protected Types

typedef actionlib::ActionServer< control_msgs::FollowJointTrajectoryAction > ActionServer
 
typedef boost::shared_ptr< ActionServerActionServerPtr
 
typedef ActionServer::GoalHandle GoalHandle
 
typedef HardwareInterfaceAdapter< HardwareInterface, typename Segment::StateHwIfaceAdapter
 
typedef HardwareInterface::ResourceHandleType JointHandle
 
typedef trajectory_msgs::JointTrajectory::ConstPtr JointTrajectoryConstPtr
 
typedef realtime_tools::RealtimeServerGoalHandle< control_msgs::FollowJointTrajectoryAction > RealtimeGoalHandle
 
typedef boost::shared_ptr< RealtimeGoalHandleRealtimeGoalHandlePtr
 
typedef Segment::Scalar Scalar
 
typedef JointTrajectorySegment< SegmentImpl > Segment
 
typedef realtime_tools::RealtimePublisher< control_msgs::JointTrajectoryControllerState > StatePublisher
 
typedef boost::scoped_ptr< StatePublisherStatePublisherPtr
 
typedef std::vector< TrajectoryPerJointTrajectory
 
typedef realtime_tools::RealtimeBox< TrajectoryPtrTrajectoryBox
 
typedef std::vector< SegmentTrajectoryPerJoint
 
typedef boost::shared_ptr< TrajectoryPerJointTrajectoryPerJointPtr
 
typedef boost::shared_ptr< TrajectoryTrajectoryPtr
 

Protected Member Functions

virtual void cancelCB (GoalHandle gh)
 
virtual void goalCB (GoalHandle gh)
 
virtual void preemptActiveGoal ()
 
void publishState (const ros::Time &time)
 Publish current controller state at a throttled frequency. More...
 
virtual bool queryStateService (control_msgs::QueryTrajectoryState::Request &req, control_msgs::QueryTrajectoryState::Response &resp)
 
void setHoldPosition (const ros::Time &time, RealtimeGoalHandlePtr gh=RealtimeGoalHandlePtr())
 Hold the current position. More...
 
virtual void trajectoryCommandCB (const JointTrajectoryConstPtr &msg)
 
virtual bool updateTrajectoryCommand (const JointTrajectoryConstPtr &msg, RealtimeGoalHandlePtr gh, std::string *error_string=0)
 
- Protected Member Functions inherited from controller_interface::Controller< HardwareInterface >
std::string getHardwareInterfaceType () const
 
virtual bool initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources)
 

Protected Attributes

ros::Duration action_monitor_period_
 
ActionServerPtr action_server_
 
bool allow_partial_joints_goal_
 
std::vector< bool > angle_wraparound_
 Whether controlled joints wrap around or not. More...
 
ros::NodeHandle controller_nh_
 
TrajectoryBox curr_trajectory_box_
 
Segment::State current_state_
 Preallocated workspace variable. More...
 
SegmentTolerances< Scalardefault_tolerances_
 Default trajectory segment tolerances. More...
 
Segment::State desired_joint_state_
 Preallocated workspace variable. More...
 
Segment::State desired_state_
 Preallocated workspace variable. More...
 
ros::Timer goal_handle_timer_
 
TrajectoryPtr hold_trajectory_ptr_
 Last hold trajectory values. More...
 
HwIfaceAdapter hw_iface_adapter_
 Adapts desired trajectory state to HW interface. More...
 
std::vector< std::string > joint_names_
 Controlled joint names. More...
 
std::vector< JointHandlejoints_
 Handles to controlled joints. More...
 
ros::Time last_state_publish_time_
 
std::string name_
 Controller name. More...
 
ros::ServiceServer query_state_service_
 
RealtimeGoalHandlePtr rt_active_goal_
 Currently active action goal, if any. More...
 
Segment::State state_error_
 Preallocated workspace variable. More...
 
Segment::State state_joint_error_
 Preallocated workspace variable. More...
 
StatePublisherPtr state_publisher_
 
ros::Duration state_publisher_period_
 
Segment::Time stop_trajectory_duration_
 Duration for stop ramp. If zero, the controller stops at the actual position. More...
 
boost::dynamic_bitset successful_joint_traj_
 
realtime_tools::RealtimeBuffer< TimeDatatime_data_
 
ros::Subscriber trajectory_command_sub_
 
bool verbose_
 Hard coded verbose flag to help in debugging. More...
 

Additional Inherited Members

- Public Types inherited from controller_interface::ControllerBase
typedef std::vector< hardware_interface::InterfaceResourcesClaimedResources
 
- Public Attributes inherited from controller_interface::ControllerBase
 CONSTRUCTED
 
 INITIALIZED
 
 RUNNING
 
enum controller_interface::ControllerBase:: { ... }  state_
 

Detailed Description

template<class SegmentImpl, class HardwareInterface>
class joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >

Controller for executing joint-space trajectories on a group of joints.

Note
Non-developer documentation and usage instructions can be found in the package's ROS wiki page.
Template Parameters
SegmentImplTrajectory segment representation to use. The type must comply with the following structure:
class FooSegment
{
public:
// Required types
typedef double Scalar; // Scalar can be anything convertible to double
typedef Scalar Time;
typedef PosVelAccState<Scalar> State;
// Default constructor
FooSegment();
// Constructor from start and end states (boundary conditions)
FooSegment(const Time& start_time,
const State& start_state,
const Time& end_time,
const State& end_state);
// Start and end states initializer (the guts of the above constructor)
// May throw std::invalid_argument if parameters are invalid
void init(const Time& start_time,
const State& start_state,
const Time& end_time,
const State& end_state);
// Sampler (realtime-safe)
void sample(const Time& time, State& state) const;
// Accesors (realtime-safe)
Time startTime() const;
Time endTime() const;
unsigned int size() const;
};
HardwareInterfaceController hardware interface. Currently hardware_interface::PositionJointInterface, hardware_interface::VelocityJointInterface, and hardware_interface::EffortJointInterface are supported out-of-the-box.

Definition at line 127 of file joint_trajectory_controller.h.

Member Typedef Documentation

template<class SegmentImpl , class HardwareInterface >
typedef actionlib::ActionServer<control_msgs::FollowJointTrajectoryAction> joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::ActionServer
protected

Definition at line 160 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
typedef boost::shared_ptr<ActionServer> joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::ActionServerPtr
protected

Definition at line 161 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
typedef ActionServer::GoalHandle joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::GoalHandle
protected

Definition at line 162 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
typedef HardwareInterfaceAdapter<HardwareInterface, typename Segment::State> joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::HwIfaceAdapter
protected

Definition at line 177 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
typedef HardwareInterface::ResourceHandleType joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::JointHandle
protected

Definition at line 178 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
typedef trajectory_msgs::JointTrajectory::ConstPtr joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::JointTrajectoryConstPtr
protected

Definition at line 165 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
typedef realtime_tools::RealtimeServerGoalHandle<control_msgs::FollowJointTrajectoryAction> joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::RealtimeGoalHandle
protected

Definition at line 163 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
typedef boost::shared_ptr<RealtimeGoalHandle> joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::RealtimeGoalHandlePtr
protected

Definition at line 164 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
typedef Segment::Scalar joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::Scalar
protected

Definition at line 175 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
typedef JointTrajectorySegment<SegmentImpl> joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::Segment
protected

Definition at line 169 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
typedef realtime_tools::RealtimePublisher<control_msgs::JointTrajectoryControllerState> joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::StatePublisher
protected

Definition at line 166 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
typedef boost::scoped_ptr<StatePublisher> joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::StatePublisherPtr
protected

Definition at line 167 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
typedef std::vector<TrajectoryPerJoint> joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::Trajectory
protected

Definition at line 171 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
typedef realtime_tools::RealtimeBox<TrajectoryPtr> joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::TrajectoryBox
protected

Definition at line 174 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
typedef std::vector<Segment> joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::TrajectoryPerJoint
protected

Definition at line 170 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
typedef boost::shared_ptr<TrajectoryPerJoint> joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::TrajectoryPerJointPtr
protected

Definition at line 173 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
typedef boost::shared_ptr<Trajectory> joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::TrajectoryPtr
protected

Definition at line 172 of file joint_trajectory_controller.h.

Constructor & Destructor Documentation

template<class SegmentImpl , class HardwareInterface >
joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::JointTrajectoryController ( )

Definition at line 190 of file joint_trajectory_controller_impl.h.

Member Function Documentation

template<class SegmentImpl , class HardwareInterface >
void joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::cancelCB ( GoalHandle  gh)
protectedvirtual

Definition at line 659 of file joint_trajectory_controller_impl.h.

template<class SegmentImpl , class HardwareInterface >
void joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::goalCB ( GoalHandle  gh)
protectedvirtual

Definition at line 586 of file joint_trajectory_controller_impl.h.

template<class SegmentImpl , class HardwareInterface >
bool joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::init ( HardwareInterface *  hw,
ros::NodeHandle root_nh,
ros::NodeHandle controller_nh 
)
virtual
template<class SegmentImpl , class HardwareInterface >
void joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::preemptActiveGoal ( )
inlineprotectedvirtual

Definition at line 175 of file joint_trajectory_controller_impl.h.

template<class SegmentImpl , class HardwareInterface >
void joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::publishState ( const ros::Time time)
protected

Publish current controller state at a throttled frequency.

Note
This method is realtime-safe and is meant to be called from update, as it shares data with it without any locking.

Definition at line 731 of file joint_trajectory_controller_impl.h.

template<class SegmentImpl , class HardwareInterface >
bool joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::queryStateService ( control_msgs::QueryTrajectoryState::Request &  req,
control_msgs::QueryTrajectoryState::Response &  resp 
)
protectedvirtual

Definition at line 683 of file joint_trajectory_controller_impl.h.

template<class SegmentImpl , class HardwareInterface >
void joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::setHoldPosition ( const ros::Time time,
RealtimeGoalHandlePtr  gh = RealtimeGoalHandlePtr() 
)
protected

Hold the current position.

Substitutes the current trajectory with a single-segment one going from the current position and velocity to zero velocity.

See also
parameter stop_trajectory_duration
Note
This method is realtime-safe.

Definition at line 756 of file joint_trajectory_controller_impl.h.

template<class SegmentImpl , class HardwareInterface >
void joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::starting ( const ros::Time time)
inlinevirtual

Holds the current position.

Reimplemented from controller_interface::ControllerBase.

Definition at line 133 of file joint_trajectory_controller_impl.h.

template<class SegmentImpl , class HardwareInterface >
void joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::stopping ( const ros::Time )
inlinevirtual

Cancels the active action goal, if any.

Reimplemented from controller_interface::ControllerBase.

Definition at line 160 of file joint_trajectory_controller_impl.h.

template<class SegmentImpl , class HardwareInterface >
void joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::trajectoryCommandCB ( const JointTrajectoryConstPtr msg)
inlineprotectedvirtual

Definition at line 167 of file joint_trajectory_controller_impl.h.

template<class SegmentImpl , class HardwareInterface >
void joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::update ( const ros::Time time,
const ros::Duration period 
)
virtual
template<class SegmentImpl , class HardwareInterface >
bool joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::updateTrajectoryCommand ( const JointTrajectoryConstPtr msg,
RealtimeGoalHandlePtr  gh,
std::string *  error_string = 0 
)
protectedvirtual

Definition at line 500 of file joint_trajectory_controller_impl.h.

Member Data Documentation

template<class SegmentImpl , class HardwareInterface >
ros::Duration joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::action_monitor_period_
protected

Definition at line 209 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
ActionServerPtr joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::action_server_
protected

Definition at line 218 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
bool joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::allow_partial_joints_goal_
protected

Definition at line 213 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
std::vector<bool> joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::angle_wraparound_
protected

Whether controlled joints wrap around or not.

Definition at line 183 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
ros::NodeHandle joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::controller_nh_
protected

Definition at line 216 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
TrajectoryBox joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::curr_trajectory_box_
protected

Thread-safe container with a smart pointer to trajectory currently being followed. Can be either a hold trajectory or a trajectory received from a ROS message.

We store the hold trajectory in a separate class member because the starting(time) method must be realtime-safe. The (single segment) hold trajectory is preallocated at initialization time and its size is kept unchanged.

Definition at line 197 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
Segment::State joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::current_state_
protected

Preallocated workspace variable.

Definition at line 200 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
SegmentTolerances<Scalar> joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::default_tolerances_
protected

Default trajectory segment tolerances.

Definition at line 185 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
Segment::State joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::desired_joint_state_
protected

Preallocated workspace variable.

Definition at line 203 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
Segment::State joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::desired_state_
protected

Preallocated workspace variable.

Definition at line 201 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
ros::Timer joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::goal_handle_timer_
protected

Definition at line 222 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
TrajectoryPtr joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::hold_trajectory_ptr_
protected

Last hold trajectory values.

Definition at line 198 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
HwIfaceAdapter joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::hw_iface_adapter_
protected

Adapts desired trajectory state to HW interface.

Definition at line 186 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
std::vector<std::string> joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::joint_names_
protected

Controlled joint names.

Definition at line 184 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
std::vector<JointHandle> joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::joints_
protected

Handles to controlled joints.

Definition at line 182 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
ros::Time joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::last_state_publish_time_
protected

Definition at line 223 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
std::string joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::name_
protected

Controller name.

Definition at line 181 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
ros::ServiceServer joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::query_state_service_
protected

Definition at line 219 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
RealtimeGoalHandlePtr joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::rt_active_goal_
protected

Currently active action goal, if any.

Definition at line 188 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
Segment::State joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::state_error_
protected

Preallocated workspace variable.

Definition at line 202 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
Segment::State joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::state_joint_error_
protected

Preallocated workspace variable.

Definition at line 204 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
StatePublisherPtr joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::state_publisher_
protected

Definition at line 220 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
ros::Duration joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::state_publisher_period_
protected

Definition at line 208 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
Segment::Time joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::stop_trajectory_duration_
protected

Duration for stop ramp. If zero, the controller stops at the actual position.

Definition at line 211 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
boost::dynamic_bitset joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::successful_joint_traj_
protected

Definition at line 212 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
realtime_tools::RealtimeBuffer<TimeData> joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::time_data_
protected

Definition at line 206 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
ros::Subscriber joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::trajectory_command_sub_
protected

Definition at line 217 of file joint_trajectory_controller.h.

template<class SegmentImpl , class HardwareInterface >
bool joint_trajectory_controller::JointTrajectoryController< SegmentImpl, HardwareInterface >::verbose_
protected

Hard coded verbose flag to help in debugging.

Definition at line 180 of file joint_trajectory_controller.h.


The documentation for this class was generated from the following files:


joint_trajectory_controller
Author(s): Adolfo Rodriguez Tsouroukdissian
autogenerated on Thu Apr 11 2019 03:08:37