Go to the documentation of this file.
32 #include <xpp_msgs/RobotStateCartesian.h>
41 int main(
int argc,
char *argv[])
43 ros::init(argc, argv,
"monped_publisher_node");
63 hopper.
base_.
lin.
p_.z() = 0.7 - 0.05*sin(2*M_PI/(2*T)*t);
EndeffectorsMotion ee_motion_
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
int main(int argc, char *argv[])
ROSCPP_DECL void spinOnce()
EndeffectorsContact ee_contact_
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
static const std::string robot_state_desired("/xpp/state_des")
#define ROS_INFO_STREAM(args)
Endeffectors< Vector3d > ee_forces_
static geometry_msgs::Quaternion ToRos(const Eigen::Quaterniond xpp)
StateLin3d & at(EndeffectorID ee)
uint32_t getNumSubscribers() const
xpp_examples
Author(s): Alexander W. Winkler
autogenerated on Wed Mar 2 2022 01:14:21