monoped_pub.cc
Go to the documentation of this file.
1 /******************************************************************************
2 Copyright (c) 2017, Alexander W. Winkler. All rights reserved.
3 
4 Redistribution and use in source and binary forms, with or without
5 modification, are permitted provided that the following conditions are met:
6 
7 * Redistributions of source code must retain the above copyright notice, this
8  list of conditions and the following disclaimer.
9 
10 * Redistributions in binary form must reproduce the above copyright notice,
11  this list of conditions and the following disclaimer in the documentation
12  and/or other materials provided with the distribution.
13 
14 * Neither the name of the copyright holder nor the names of its
15  contributors may be used to endorse or promote products derived from
16  this software without specific prior written permission.
17 
18 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 ******************************************************************************/
29 
30 #include <ros/ros.h>
31 
32 #include <xpp_msgs/RobotStateCartesian.h>
33 #include <xpp_msgs/topic_names.h>
34 
35 #include <xpp_states/convert.h>
37 
38 
39 using namespace xpp;
40 
41 int main(int argc, char *argv[])
42 {
43  ros::init(argc, argv, "monped_publisher_node");
44 
46  ros::Publisher state_pub = n.advertise<xpp_msgs::RobotStateCartesian>(xpp_msgs::robot_state_desired, 1);
47  ROS_INFO_STREAM("Waiting for Subscriber...");
48  while(ros::ok() && state_pub.getNumSubscribers() == 0)
49  ros::Rate(100).sleep();
50  ROS_INFO_STREAM("Subscriber to initial state connected");
51 
52 
53  // visualize the state of a one-legged hopper
54  RobotStateCartesian hopper(1);
55 
56  // publishes a sequence of states for a total duration of T spaced 0.01s apart.
57  double T = 2.0;
58  double t = 0.0;
59  double dt = 0.01;
60  while (t < T)
61  {
62  // base and foot follow half a sine motion up and down
63  hopper.base_.lin.p_.z() = 0.7 - 0.05*sin(2*M_PI/(2*T)*t);
64  hopper.ee_motion_.at(0).p_.z() = 0.1*sin(2*M_PI/(2*T)*t);
65  hopper.ee_forces_.at(0).z() = 100; // N
66  hopper.ee_contact_.at(0) = true;
67 
68  state_pub.publish(Convert::ToRos(hopper));
69 
70  ros::spinOnce();
71  ros::Duration(dt).sleep(); // pause loop so visualization has correct speed.
72  t += dt;
73  }
74 
75 
76  return 0;
77 }
78 
xpp::RobotStateCartesian::ee_motion_
EndeffectorsMotion ee_motion_
ros::Publisher
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
xpp::State3d::lin
StateLin3d lin
main
int main(int argc, char *argv[])
Definition: monoped_pub.cc:41
ros::spinOnce
ROSCPP_DECL void spinOnce()
xpp::StateLinXd::p_
VectorXd p_
xpp::RobotStateCartesian::ee_contact_
EndeffectorsContact ee_contact_
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::ok
ROSCPP_DECL bool ok()
xpp::RobotStateCartesian::base_
State3d base_
xpp_msgs::robot_state_desired
static const std::string robot_state_desired("/xpp/state_des")
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
xpp
ros::Rate::sleep
bool sleep()
xpp::RobotStateCartesian::ee_forces_
Endeffectors< Vector3d > ee_forces_
xpp::RobotStateCartesian
xpp::Convert::ToRos
static geometry_msgs::Quaternion ToRos(const Eigen::Quaterniond xpp)
Endeffectors< StateLin3d >::at
StateLin3d & at(EndeffectorID ee)
ros::Rate
convert.h
ros::Duration::sleep
bool sleep() const
topic_names.h
robot_state_cartesian.h
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
ros::Duration
ros::NodeHandle


xpp_examples
Author(s): Alexander W. Winkler
autogenerated on Wed Mar 2 2022 01:14:21